diff --git a/.gitignore b/.gitignore
index 0c36d682f..df6985be8 100644
--- a/.gitignore
+++ b/.gitignore
@@ -32,6 +32,7 @@ share/python-wheels/
.installed.cfg
*.egg
MANIFEST
+.idea/
# PyInstaller
# Usually these files are written by a python script from a template
@@ -134,6 +135,7 @@ venv/
ENV/
env.bak/
venv.bak/
+*.DS_Store
# Spyder project settings
.spyderproject
@@ -165,3 +167,11 @@ cython_debug/
# and can be added to the global gitignore or merged into this file. For a more nuclear
# option (not recommended) you can uncomment the following to ignore the entire idea folder.
#.idea/
+
+.vscode/
+setup/zed_sdk.run
+
+cuda/
+#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/gem_e4.yaml b/GEMstack/knowledge/calibration/gem_e4.yaml
index d0954dc06..b43a0f698 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_oak.yaml b/GEMstack/knowledge/calibration/gem_e4_oak.yaml
index cb9a6c0d0..b9ba2d7fd 100644
--- a/GEMstack/knowledge/calibration/gem_e4_oak.yaml
+++ b/GEMstack/knowledge/calibration/gem_e4_oak.yaml
@@ -1,3 +1,8 @@
+# Calibration for front rgb camera->vehicle on GEM e4
+# Calibration Date: 02/25/2025 05:09
+
reference: rear_axle_center # rear axle center
-rotation: [[0,0,1],[-1,0,0],[0,-1,0]] # rotation matrix mapping z to forward, x to left, y to down, guesstimated
-center_position: [1.78,0,1.58] # meters, center camera, guesstimated
+rotation: [[ 0.00349517, -0.03239524, 0.99946903], # rotation component of camera -> vehicle matrix
+ [-0.99996547, 0.00742285, 0.0037375],
+ [-0.00753999, -0.99944757, -0.03236817]] # rotation matrix mapping z to forward, x to left, y to down, guesstimated
+center_position: [ 1.75864913, 0.01238124, 1.54408419] # translation component of camera -> vehicle matrix (in meters)
diff --git a/GEMstack/knowledge/calibration/gem_e4_ouster.yaml b/GEMstack/knowledge/calibration/gem_e4_ouster.yaml
index 5987373a6..4e919502f 100644
--- a/GEMstack/knowledge/calibration/gem_e4_ouster.yaml
+++ b/GEMstack/knowledge/calibration/gem_e4_ouster.yaml
@@ -1,3 +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,2.03] # meters, calibrated by Hang's watchful eye
-rotation: [[1,0,0],[0,1,0],[0,0,1]] #rotation matrix mapping lidar frame to vehicle frame
\ No newline at end of file
+position: [1.1, 0.03773044170906172, 1.9525244316515322] # top lidar to vehicle matrix translation component
+rotation: [[ 0.99941328, 0.02547416, 0.02289458], # top lidar to vehicle matrix rotation component
+ [-0.02530855, 0.99965159, -0.00749488],
+ [-0.02307753, 0.00691106, 0.99970979]]
diff --git a/GEMstack/knowledge/defaults/computation_graph.yaml b/GEMstack/knowledge/defaults/computation_graph.yaml
index d7a606326..683dc0c7b 100644
--- a/GEMstack/knowledge/defaults/computation_graph.yaml
+++ b/GEMstack/knowledge/defaults/computation_graph.yaml
@@ -31,7 +31,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]
@@ -52,3 +52,6 @@ components:
- trajectory_tracking:
inputs: [vehicle, trajectory]
outputs:
+ - signaling:
+ inputs: [intent]
+ outputs:
diff --git a/GEMstack/knowledge/defaults/current.yaml b/GEMstack/knowledge/defaults/current.yaml
index c886288be..87c22c0e4 100644
--- a/GEMstack/knowledge/defaults/current.yaml
+++ b/GEMstack/knowledge/defaults/current.yaml
@@ -1,34 +1,54 @@
# ********* Main settings entry point for behavior stack ***********
-
-# Configure settings for the vehicle / vehicle model
-vehicle: !include ../vehicle/gem_e4.yaml
-
-#arguments for algorithm components here
-model_predictive_controller:
- dt: 0.1
- lookahead: 20
-control:
- recovery:
- brake_amount : 0.5
- brake_speed : 2.0
- pure_pursuit:
- lookahead: 2.0
- lookahead_scale: 3.0
- crosstrack_gain: 1.0
- desired_speed: trajectory
- longitudinal_control:
- pid_p: 1.0
- pid_i: 0.1
- pid_d: 0.0
-
-#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
- #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
+
+ # Configure settings for the vehicle / vehicle model
+ vehicle: !include ../vehicle/gem_e4.yaml
+
+ #arguments for algorithm components here
+ model_predictive_controller:
+ dt: 0.1
+ lookahead: 20
+ control:
+ recovery:
+ brake_amount : 0.5
+ brake_speed : 2.0
+ pure_pursuit:
+ lookahead: 2.0
+ lookahead_scale: 2.0
+ crosstrack_gain: 0.3
+ desired_speed: trajectory #racing
+ launch_control:
+ enable: 1
+ stage_duration: 0.5
+ # Stanley controller parameters (fine tune this)
+ stanley:
+ control_gain: 0.1
+ softening_gain: 0.2
+ desired_speed: racing # Speed reference source: can be "trajectory", "path", "racing" or a constant value
+
+ longitudinal_control:
+ 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.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
diff --git a/GEMstack/knowledge/routes/circle_10m_rad.csv b/GEMstack/knowledge/routes/circle_10m_rad.csv
new file mode 100644
index 000000000..6c1c629e6
--- /dev/null
+++ b/GEMstack/knowledge/routes/circle_10m_rad.csv
@@ -0,0 +1,100 @@
+10.0,0.0
+9.980267284282716,0.6279051952931337
+9.921147013144777,1.2533323356430426
+9.822872507286887,1.8738131458572465
+9.685831611286313,2.4868988716485485
+9.510565162951536,3.0901699437494745
+9.297764858882513,3.68124552684678
+9.048270524660193,4.257792915650727
+8.763066800438635,4.817536741017153
+8.443279255020151,5.3582679497899655
+8.090169943749476,5.87785252292473
+7.705132427757894,6.3742398974868975
+7.289686274214117,6.845471059286887
+6.845471059286887,7.289686274214117
+6.374239897486897,7.705132427757894
+5.87785252292473,8.090169943749476
+5.3582679497899655,8.443279255020151
+4.817536741017151,8.763066800438637
+4.257792915650727,9.048270524660195
+3.681245526846779,9.297764858882514
+3.090169943749475,9.510565162951536
+2.486898871648548,9.685831611286313
+1.8738131458572451,9.822872507286887
+1.2533323356430426,9.921147013144777
+0.6279051952931329,9.980267284282716
+-1.6081226496766366e-15,9.999999999999998
+-0.627905195293134,9.980267284282716
+-1.2533323356430437,9.921147013144777
+-1.8738131458572485,9.822872507286887
+-2.486898871648549,9.685831611286313
+-3.0901699437494763,9.510565162951536
+-3.68124552684678,9.297764858882514
+-4.257792915650728,9.048270524660195
+-4.817536741017154,8.763066800438635
+-5.358267949789967,8.44327925502015
+-5.877852522924729,8.090169943749476
+-6.374239897486897,7.705132427757894
+-6.845471059286887,7.289686274214116
+-7.289686274214117,6.845471059286886
+-7.705132427757895,6.374239897486894
+-8.090169943749475,5.877852522924732
+-8.443279255020151,5.3582679497899655
+-8.763066800438637,4.817536741017151
+-9.048270524660195,4.257792915650725
+-9.297764858882514,3.6812455268467774
+-9.510565162951538,3.090169943749471
+-9.685831611286313,2.4868988716485485
+-9.822872507286887,1.8738131458572458
+-9.921147013144777,1.2533323356430408
+-9.980267284282716,0.6279051952931314
+-10.0,-3.216245299353273e-15
+-9.980267284282716,-0.6279051952931334
+-9.921147013144777,-1.253332335643043
+-9.822872507286887,-1.873813145857248
+-9.685831611286313,-2.4868988716485503
+-9.510565162951535,-3.090169943749478
+-9.297764858882513,-3.6812455268467836
+-9.048270524660193,-4.257792915650727
+-8.763066800438635,-4.817536741017154
+-8.44327925502015,-5.358267949789967
+-8.090169943749473,-5.877852522924733
+-7.705132427757891,-6.3742398974869
+-7.289686274214117,-6.845471059286887
+-6.845471059286886,-7.289686274214117
+-6.374239897486895,-7.705132427757895
+-5.877852522924733,-8.090169943749475
+-5.358267949789962,-8.443279255020153
+-4.817536741017153,-8.763066800438635
+-4.257792915650722,-9.048270524660197
+-3.6812455268467783,-9.297764858882514
+-3.0901699437494763,-9.510565162951535
+-2.4868988716485445,-9.685831611286313
+-1.8738131458572465,-9.822872507286887
+-1.2533323356430373,-9.921147013144777
+-0.6279051952931319,-9.980267284282716
+-1.8369701987210296e-15,-10.0
+0.6279051952931372,-9.980267284282716
+1.2533323356430424,-9.921147013144777
+1.8738131458572516,-9.822872507286887
+2.48689887164855,-9.685831611286313
+3.0901699437494727,-9.510565162951538
+3.681245526846783,-9.297764858882513
+4.257792915650727,-9.048270524660195
+4.817536741017157,-8.763066800438633
+5.358267949789966,-8.44327925502015
+5.877852522924735,-8.090169943749471
+6.374239897486898,-7.705132427757891
+6.845471059286886,-7.289686274214117
+7.289686274214119,-6.845471059286883
+7.705132427757894,-6.374239897486895
+8.09016994374948,-5.877852522924725
+8.443279255020153,-5.358267949789962
+8.763066800438635,-4.817536741017153
+9.048270524660197,-4.257792915650722
+9.297764858882513,-3.6812455268467787
+9.510565162951538,-3.0901699437494683
+9.685831611286313,-2.4868988716485454
+9.822872507286887,-1.8738131458572471
+9.921147013144777,-1.253332335643038
+9.980267284282716,-0.6279051952931326
diff --git a/GEMstack/knowledge/routes/circle_20m_rad.csv b/GEMstack/knowledge/routes/circle_20m_rad.csv
new file mode 100644
index 000000000..6b28cb31a
--- /dev/null
+++ b/GEMstack/knowledge/routes/circle_20m_rad.csv
@@ -0,0 +1,100 @@
+20.0,0.0
+19.960534568565432,1.2558103905862674
+19.842294026289558,2.506664671286085
+19.645745014573773,3.7476262917144925
+19.37166322257262,4.973797743297096
+19.02113032590307,6.180339887498948
+18.595529717765025,7.362491053693559
+18.09654104932039,8.515585831301454
+17.526133600877273,9.635073482034306
+16.886558510040302,10.716535899579933
+16.18033988749895,11.755705045849464
+15.410264855515782,12.748479794973795
+14.579372548428232,13.690942118573775
+13.690942118573773,14.579372548428232
+12.748479794973793,15.410264855515784
+11.75570504584946,16.18033988749895
+10.716535899579931,16.886558510040302
+9.635073482034302,17.526133600877273
+8.515585831301454,18.096541049320393
+7.3624910536935575,18.59552971776503
+6.180339887498949,19.02113032590307
+4.973797743297094,19.37166322257262
+3.7476262917144902,19.645745014573773
+2.506664671286085,19.842294026289558
+1.255810390586266,19.960534568565432
+-3.2162452993532727e-15,20.0
+-1.255810390586268,19.960534568565432
+-2.5066646712860874,19.842294026289554
+-3.7476262917144965,19.645745014573773
+-4.973797743297097,19.37166322257262
+-6.180339887498951,19.02113032590307
+-7.362491053693559,18.595529717765025
+-8.515585831301454,18.09654104932039
+-9.635073482034308,17.52613360087727
+-10.716535899579938,16.8865585100403
+-11.75570504584946,16.18033988749895
+-12.748479794973795,15.410264855515784
+-13.690942118573775,14.579372548428228
+-14.579372548428234,13.69094211857377
+-15.410264855515788,12.74847979497379
+-16.180339887498945,11.755705045849465
+-16.886558510040302,10.716535899579933
+-17.526133600877273,9.635073482034304
+-18.096541049320393,8.51558583130145
+-18.59552971776503,7.362491053693555
+-19.021130325903073,6.180339887498942
+-19.37166322257262,4.973797743297096
+-19.645745014573773,3.7476262917144916
+-19.842294026289558,2.5066646712860816
+-19.960534568565432,1.2558103905862628
+-20.0,-6.432490598706546e-15
+-19.960534568565432,-1.255810390586267
+-19.842294026289558,-2.5066646712860856
+-19.645745014573773,-3.7476262917144956
+-19.37166322257262,-4.973797743297101
+-19.02113032590307,-6.180339887498954
+-18.595529717765025,-7.362491053693566
+-18.09654104932039,-8.515585831301454
+-17.52613360087727,-9.635073482034308
+-16.8865585100403,-10.716535899579934
+-16.180339887498945,-11.755705045849467
+-15.41026485551578,-12.7484797949738
+-14.579372548428232,-13.690942118573775
+-13.690942118573773,-14.579372548428232
+-12.74847979497379,-15.410264855515788
+-11.755705045849465,-16.180339887498945
+-10.716535899579927,-16.886558510040306
+-9.635073482034306,-17.526133600877273
+-8.515585831301443,-18.096541049320397
+-7.362491053693557,-18.59552971776503
+-6.180339887498951,-19.02113032590307
+-4.973797743297089,-19.371663222572625
+-3.7476262917144925,-19.645745014573773
+-2.5066646712860745,-19.842294026289558
+-1.255810390586264,-19.960534568565432
+-3.673940397442059e-15,-20.0
+1.2558103905862743,-19.960534568565432
+2.5066646712860847,-19.842294026289558
+3.7476262917145027,-19.645745014573773
+4.973797743297099,-19.37166322257262
+6.180339887498945,-19.021130325903073
+7.3624910536935655,-18.595529717765025
+8.515585831301452,-18.096541049320393
+9.635073482034315,-17.526133600877266
+10.716535899579934,-16.8865585100403
+11.755705045849474,-16.18033988749894
+12.7484797949738,-15.41026485551578
+13.690942118573773,-14.579372548428232
+14.579372548428237,-13.690942118573766
+15.410264855515788,-12.748479794973793
+16.180339887498956,-11.755705045849451
+16.886558510040306,-10.716535899579927
+17.526133600877273,-9.635073482034306
+18.096541049320393,-8.515585831301443
+18.59552971776503,-7.3624910536935575
+19.021130325903076,-6.180339887498936
+19.371663222572625,-4.97379774329709
+19.645745014573773,-3.747626291714494
+19.842294026289558,-2.506664671286076
+19.960534568565432,-1.2558103905862652
diff --git a/GEMstack/knowledge/routes/circle_5m_rad.csv b/GEMstack/knowledge/routes/circle_5m_rad.csv
new file mode 100644
index 000000000..061b3b441
--- /dev/null
+++ b/GEMstack/knowledge/routes/circle_5m_rad.csv
@@ -0,0 +1,100 @@
+5.0,0.0
+4.990133642141358,0.31395259764656686
+4.9605735065723895,0.6266661678215213
+4.911436253643443,0.9369065729286231
+4.842915805643155,1.243449435824274
+4.755282581475767,1.545084971874737
+4.648882429441256,1.8406227634233898
+4.524135262330097,2.1288964578253635
+4.381533400219318,2.4087683705085765
+4.221639627510076,2.679133974894983
+4.045084971874737,2.938926261462366
+3.8525662138789456,3.1871199487434487
+3.644843137107058,3.4227355296434436
+3.422735529643443,3.644843137107058
+3.1871199487434483,3.852566213878946
+2.938926261462365,4.045084971874737
+2.6791339748949827,4.221639627510076
+2.4087683705085756,4.381533400219318
+2.1288964578253635,4.524135262330098
+1.8406227634233894,4.648882429441257
+1.5450849718747373,4.755282581475767
+1.2434494358242736,4.842915805643155
+0.9369065729286226,4.911436253643443
+0.6266661678215213,4.9605735065723895
+0.3139525976465665,4.990133642141358
+-8.040613248383182e-16,5.0
+-0.313952597646567,4.990133642141358
+-0.6266661678215218,4.960573506572389
+-0.9369065729286241,4.911436253643443
+-1.2434494358242743,4.842915805643155
+-1.5450849718747377,4.755282581475767
+-1.8406227634233898,4.648882429441256
+-2.1288964578253635,4.524135262330097
+-2.408768370508577,4.381533400219317
+-2.6791339748949845,4.221639627510075
+-2.938926261462365,4.045084971874737
+-3.1871199487434487,3.852566213878946
+-3.4227355296434436,3.644843137107057
+-3.6448431371070584,3.4227355296434423
+-3.852566213878947,3.1871199487434474
+-4.045084971874736,2.9389262614623664
+-4.221639627510076,2.679133974894983
+-4.381533400219318,2.408768370508576
+-4.524135262330098,2.1288964578253626
+-4.648882429441257,1.8406227634233887
+-4.755282581475768,1.5450849718747355
+-4.842915805643155,1.243449435824274
+-4.911436253643443,0.9369065729286229
+-4.9605735065723895,0.6266661678215204
+-4.990133642141358,0.3139525976465657
+-5.0,-1.6081226496766366e-15
+-4.990133642141358,-0.31395259764656674
+-4.9605735065723895,-0.6266661678215214
+-4.911436253643443,-0.9369065729286239
+-4.842915805643155,-1.2434494358242751
+-4.755282581475767,-1.5450849718747386
+-4.648882429441256,-1.8406227634233916
+-4.524135262330097,-2.1288964578253635
+-4.381533400219317,-2.408768370508577
+-4.221639627510075,-2.6791339748949836
+-4.045084971874736,-2.938926261462367
+-3.852566213878945,-3.18711994874345
+-3.644843137107058,-3.4227355296434436
+-3.422735529643443,-3.644843137107058
+-3.1871199487434474,-3.852566213878947
+-2.9389262614623664,-4.045084971874736
+-2.679133974894982,-4.2216396275100765
+-2.4087683705085765,-4.381533400219318
+-2.128896457825361,-4.524135262330099
+-1.8406227634233892,-4.648882429441257
+-1.5450849718747377,-4.755282581475767
+-1.2434494358242723,-4.842915805643156
+-0.9369065729286231,-4.911436253643443
+-0.6266661678215186,-4.9605735065723895
+-0.313952597646566,-4.990133642141358
+-9.184850993605148e-16,-5.0
+0.3139525976465686,-4.990133642141358
+0.6266661678215212,-4.9605735065723895
+0.9369065729286257,-4.911436253643443
+1.2434494358242747,-4.842915805643155
+1.5450849718747361,-4.755282581475768
+1.8406227634233914,-4.648882429441256
+2.128896457825363,-4.524135262330098
+2.4087683705085787,-4.3815334002193165
+2.6791339748949836,-4.221639627510075
+2.9389262614623686,-4.045084971874735
+3.18711994874345,-3.852566213878945
+3.422735529643443,-3.644843137107058
+3.6448431371070593,-3.4227355296434414
+3.852566213878947,-3.1871199487434483
+4.045084971874739,-2.938926261462363
+4.2216396275100765,-2.679133974894982
+4.381533400219318,-2.4087683705085765
+4.524135262330098,-2.128896457825361
+4.648882429441257,-1.8406227634233894
+4.755282581475769,-1.545084971874734
+4.842915805643156,-1.2434494358242725
+4.911436253643443,-0.9369065729286234
+4.9605735065723895,-0.626666167821519
+4.990133642141358,-0.3139525976465663
diff --git a/GEMstack/knowledge/routes/figure8.csv b/GEMstack/knowledge/routes/figure8.csv
new file mode 100644
index 000000000..a19aedcd8
--- /dev/null
+++ b/GEMstack/knowledge/routes/figure8.csv
@@ -0,0 +1,200 @@
+-7.0710678118654755,7.071067811865475
+-7.2906556139397285,6.844431415617231
+-7.502308944661675,6.611639328565266
+-7.705152494913562,6.373587931399371
+-7.898325044373529,6.13117354038889
+-8.080982947051604,5.88528888686235
+-8.25230356767972,5.6368196318881
+-8.411488655184105,5.386640929976428
+-8.55776763969854,5.135614055407286
+-8.690400839861038,4.884583104517498
+-8.808682567473495,4.63437178695796
+-8.911944116992771,4.385780318556234
+-8.999556627760255,4.139582427994652
+-9.070933807364344,3.8965224890402577
+-9.12553450506384,3.65731278954247
+-9.162865124778294,3.422630947849536
+-9.182481867771463,3.1931174866877035
+-9.18399279581362,2.9693735739001195
+-9.167059706305327,2.7519589387584693
+-9.131399811576024,2.541389971841754
+-9.076787215333287,2.338138015726586
+-9.003054180029041,2.142627852954777
+-8.910092179725005,1.9552363969398612
+-8.797852733877264,1.7762915906480434
+-8.666348018316427,1.6060715170438167
+-8.515651250571414,1.4448037244299101
+-8.345896847568358,1.2926647689384532
+-8.157280354627865,1.1497799755490092
+-7.950058145580334,1.0162234181227694
+-7.72454689471666,0.8920181180543993
+-7.48112282218691,0.7771364602573145
+-7.220220715348916,0.6715008243179756
+-6.942332729448554,0.5749844277838516
+-6.648006971880344,0.48741237769124446
+-6.337845875127566,0.40856292559692964
+-6.012504364311742,0.3381689205545477
+-5.672687826088908,0.27591945367658344
+-5.319149886411543,0.22146168714843872
+-4.952690005426821,0.1744028598158298
+-4.5741508985015,0.13431246075351044
+-4.184415793048013,0.10072456154483156
+-3.784405531472644,0.07314029736083127
+-3.375075531172583,0.05103048632677254
+-2.9574126130714227,0.03383837610581075
+-2.5324317107003727,0.0209825061160398
+-2.101172472303035,0.01185967333046567
+-1.6646957688628319,0.005847989191503644
+-1.224080121322797,0.0023100148039367774
+-0.7804180605858775,0.0005959612544599313
+-0.3348124341485519,4.69416431974623e-05
+0.2232546531379846,-3.4775920885465883e-06
+1.1155779279562612,-0.00043453652732550196
+2.005122325691386,-0.0025320070504719627
+2.8896746304541985,-0.007620297045278557
+3.7670385349273756,-0.01700890073662653
+4.6350420699393595,-0.03198585311115387
+5.49154494132252,-0.05381127418390186
+6.334445746125748,-0.08371103016248593
+7.161689040726918,-0.12287053808868764
+7.97127223397421,-0.17242873995852737
+8.761252279174599,-0.23347227163807283
+9.529752139540019,-0.3070298511062006
+10.274967002594085,-0.3940669096704861
+10.995170220031003,-0.4954804888217348
+11.688718950599176,-0.6120944243204658
+12.354059484751527,-0.7446548379490805
+12.989732231057182,-0.8938259561212369
+13.5943763457005,-1.0601862732199647
+14.166733987797977,-1.2442250761436462
+14.705654184735884,-1.446339345079779
+15.21009629326522,-1.6668310440060212
+15.67913304368062,-1.9059048128428548
+16.111953156048813,-2.163666071558234
+16.507863519134226,-2.4401195448584856
+16.866290924387744,-2.7351682143983016
+17.18678334911195,-3.048612703712158
+17.469010784686596,-3.3801510993177653
+17.71276560752314,-3.7293792096751686
+17.91796249221132,-4.095791261910843
+18.084637868115514,-4.478781034440925
+18.21294892246776,-4.877643421859495
+18.303172154780448,-5.291576426702616
+18.355701489157553,-5.719683570964906
+18.37104595281231,-6.160976718538519
+18.34982693079418,-6.6143792980723
+18.292775008582552,-7.078729914117767
+18.2007264158116,-7.552786332844942
+18.07461908594467,-8.035229827081785
+17.91548834821038,-8.52466986396156
+17.72446226954103,-9.019649117059142
+17.502756665610935,-9.518648783565657
+17.251669801352808,-10.02009418579633
+16.972576802528867,-10.522360635153587
+16.666923801045655,-11.02377953558188
+16.33622183772296,-11.522644702555922
+15.982040547153561,-12.017218872744364
+15.60600165011863,-12.50574037869042
+15.209772279749702,-12.98642996215177
+14.795058168249529,-13.457497699148421
+14.363596721498746,-13.917150009280299
+13.917150009280297,-14.363596721498748
+13.457497699148425,-14.795058168249525
+12.986429962151774,-15.209772279749696
+12.505740378690426,-15.606001650118628
+12.017218872744364,-15.982040547153561
+11.522644702555919,-16.33622183772296
+11.023779535581888,-16.66692380104565
+10.522360635153591,-16.972576802528863
+10.020094185796335,-17.251669801352808
+9.518648783565663,-17.502756665610935
+9.01964911705914,-17.724462269541032
+8.524669863961567,-17.91548834821038
+8.035229827081789,-18.074619085944665
+7.552786332844948,-18.200726415811594
+7.0787299141177735,-18.292775008582552
+6.614379298072299,-18.34982693079418
+6.160976718538518,-18.37104595281231
+5.71968357096491,-18.355701489157553
+5.291576426702621,-18.303172154780448
+4.877643421859499,-18.21294892246776
+4.478781034440929,-18.084637868115514
+4.0957912619108425,-17.917962492211316
+3.7293792096751748,-17.71276560752314
+3.380151099317769,-17.469010784686596
+3.048612703712161,-17.186783349111952
+2.7351682143983043,-16.86629092438774
+2.4401195448584865,-16.507863519134226
+2.163666071558236,-16.111953156048816
+1.9059048128428593,-15.679133043680622
+1.6668310440060221,-15.210096293265215
+1.4463393450797826,-14.705654184735888
+1.2442250761436453,-14.166733987797969
+1.0601862732199674,-13.594376345700503
+0.8938259561212387,-12.989732231057184
+0.7446548379490805,-12.35405948475152
+0.6120944243204676,-11.688718950599178
+0.4954804888217357,-10.995170220030998
+0.39406690967048785,-10.274967002594092
+0.3070298511062015,-9.529752139540019
+0.23347227163807283,-8.76125227917459
+0.17242873995852914,-7.9712722339742115
+0.12287053808868809,-7.161689040726909
+0.08371103016248771,-6.334445746125757
+0.05381127418390319,-5.491544941322518
+0.031985853111154317,-4.635042069939345
+0.017008900736627197,-3.767038534927379
+0.007620297045278779,-2.8896746304541896
+0.002532007050472407,-2.0051223256913895
+0.000434536527325613,-1.1155779279562583
+3.477592088574344e-06,-0.22325465313799434
+-4.694164319751781e-05,0.3348124341485501
+-0.0005959612544601534,0.7804180605858819
+-0.0023100148039368884,1.2240801213227952
+-0.005847989191504088,1.664695768862833
+-0.01185967333046567,2.10117247230303
+-0.0209825061160398,2.5324317107003713
+-0.033838376105811196,2.957412613071427
+-0.05103048632677276,3.3750755311725817
+-0.07314029736083216,3.784405531472645
+-0.10072456154483156,4.184415793048008
+-0.13431246075351133,4.574150898501502
+-0.17440285981583115,4.952690005426826
+-0.22146168714843872,5.319149886411541
+-0.27591945367658477,5.672687826088911
+-0.33816892055454817,6.012504364311738
+-0.40856292559693097,6.337845875127567
+-0.4874123776912467,6.648006971880346
+-0.5749844277838512,6.9423327294485535
+-0.6715008243179788,7.220220715348918
+-0.7771364602573145,7.481122822186904
+-0.8920181180544007,7.72454689471666
+-1.016223418122772,7.950058145580337
+-1.1497799755490097,8.157280354627865
+-1.2926647689384554,8.345896847568358
+-1.4448037244299101,8.515651250571414
+-1.6060715170438193,8.666348018316429
+-1.7762915906480434,8.797852733877262
+-1.955236396939862,8.910092179725007
+-2.14262785295478,9.003054180029043
+-2.3381380157265865,9.076787215333283
+-2.541389971841756,9.131399811576022
+-2.751958938758469,9.167059706305324
+-2.96937357390012,9.18399279581362
+-3.1931174866877075,9.182481867771461
+-3.4226309478495374,9.162865124778294
+-3.6573127895424724,9.125534505063838
+-3.896522489040256,9.070933807364344
+-4.139582427994653,8.999556627760255
+-4.385780318556237,8.911944116992768
+-4.634371786957962,8.808682567473493
+-4.884583104517502,8.690400839861034
+-5.135614055407285,8.557767639698541
+-5.38664092997643,8.411488655184103
+-5.636819631888104,8.252303567679718
+-5.88528888686235,8.080982947051606
+-6.131173540388894,7.898325044373527
+-6.373587931399368,7.705152494913563
+-6.611639328565269,7.502308944661674
+-6.844431415617234,7.290655613939725
+-7.071067811865475,7.0710678118654755
diff --git a/GEMstack/knowledge/routes/forward_50m.csv b/GEMstack/knowledge/routes/forward_50m.csv
new file mode 100644
index 000000000..6ecc0a99a
--- /dev/null
+++ b/GEMstack/knowledge/routes/forward_50m.csv
@@ -0,0 +1,51 @@
+0.0,0,0
+1.0,0,0
+2.0,0,0
+3.0,0,0
+4,0,0
+5,0,0
+6,0,0
+7,0,0
+8,0,0
+9,0,0
+10,0,0
+11,0,0
+12,0,0
+13,0,0
+14,0,0
+15,0,0
+16,0,0
+17,0,0
+18,0,0
+19,0,0
+20,0,0
+21,0,0
+22,0,0
+23,0,0
+24,0,0
+25,0,0
+26,0,0
+27,0,0
+28,0,0
+29,0,0
+30,0,0
+31,0,0
+32,0,0
+33,0,0
+34,0,0
+35,0,0
+36,0,0
+37,0,0
+38,0,0
+39,0,0
+40,0,0
+41,0,0
+42,0,0
+43,0,0
+44,0,0
+45,0,0
+46,0,0
+47,0,0
+48,0,0
+49,0,0
+50,0,0
\ No newline at end of file
diff --git a/GEMstack/knowledge/routes/forward_65m.csv b/GEMstack/knowledge/routes/forward_65m.csv
new file mode 100644
index 000000000..ee345b68a
--- /dev/null
+++ b/GEMstack/knowledge/routes/forward_65m.csv
@@ -0,0 +1,66 @@
+0,0,0
+1,0,0
+2,0,0
+3,0,0
+4,0,0
+5,0,0
+6,0,0
+7,0,0
+8,0,0
+9,0,0
+10,0,0
+11,0,0
+12,0,0
+13,0,0
+14,0,0
+15,0,0
+16,0,0
+17,0,0
+18,0,0
+19,0,0
+20,0,0
+21,0,0
+22,0,0
+23,0,0
+24,0,0
+25,0,0
+26,0,0
+27,0,0
+28,0,0
+29,0,0
+30,0,0
+31,0,0
+32,0,0
+33,0,0
+34,0,0
+35,0,0
+36,0,0
+37,0,0
+38,0,0
+39,0,0
+40,0,0
+41,0,0
+42,0,0
+43,0,0
+44,0,0
+45,0,0
+46,0,0
+47,0,0
+48,0,0
+49,0,0
+50,0,0
+51,0,0
+52,0,0
+53,0,0
+54,0,0
+55,0,0
+56,0,0
+57,0,0
+58,0,0
+59,0,0
+60,0,0
+61,0,0
+62,0,0
+63,0,0
+64,0,0
+65,0,0
diff --git a/GEMstack/knowledge/routes/racing_circle.csv b/GEMstack/knowledge/routes/racing_circle.csv
new file mode 100644
index 000000000..caa59e86e
--- /dev/null
+++ b/GEMstack/knowledge/routes/racing_circle.csv
@@ -0,0 +1,71 @@
+0,0,0
+1,0,0
+2,0,0
+3,0,0
+4,0,0
+5,0,0
+6,0,0
+7,0,0
+8,0,0
+9,0,0
+10,0,0
+11,0,0
+12,0,0
+13,0,0
+14,0,0
+15,0,0
+16,0,0
+17,0,0
+18,0,0
+19,0,0
+20,0,0
+21,0,0
+22,0,0
+23,0,0
+24,0,0
+25,0,0
+26,0,0
+27,0,0
+28,0,0
+29,0,0
+30,0,0
+31,0,0
+32,0,0
+33,0,0
+34,0,0
+35,0,0
+36,0,0
+37,0,0
+38,0,0
+39,0,0
+40,0,0
+41,0,0
+42,0,0
+43,0,0
+44,0,0
+45,0,0
+46,0,0
+47,0,0
+48,0,0
+49,0,0
+50,0,0
+51,0,0
+52,0,0
+53,0,0
+54,0,0
+55,0,0
+56,0,0
+57,0,0
+58,0,0
+59,0,0
+60,0,0
+61,0,0
+62,0,0
+63,0,0
+64,0,0
+65,0,0
+66,0,0
+67,0,0
+68,0,0
+69,0,0
+70,0,0
\ No newline at end of file
diff --git a/GEMstack/knowledge/routes/slalom.csv b/GEMstack/knowledge/routes/slalom.csv
new file mode 100644
index 000000000..caa59e86e
--- /dev/null
+++ b/GEMstack/knowledge/routes/slalom.csv
@@ -0,0 +1,71 @@
+0,0,0
+1,0,0
+2,0,0
+3,0,0
+4,0,0
+5,0,0
+6,0,0
+7,0,0
+8,0,0
+9,0,0
+10,0,0
+11,0,0
+12,0,0
+13,0,0
+14,0,0
+15,0,0
+16,0,0
+17,0,0
+18,0,0
+19,0,0
+20,0,0
+21,0,0
+22,0,0
+23,0,0
+24,0,0
+25,0,0
+26,0,0
+27,0,0
+28,0,0
+29,0,0
+30,0,0
+31,0,0
+32,0,0
+33,0,0
+34,0,0
+35,0,0
+36,0,0
+37,0,0
+38,0,0
+39,0,0
+40,0,0
+41,0,0
+42,0,0
+43,0,0
+44,0,0
+45,0,0
+46,0,0
+47,0,0
+48,0,0
+49,0,0
+50,0,0
+51,0,0
+52,0,0
+53,0,0
+54,0,0
+55,0,0
+56,0,0
+57,0,0
+58,0,0
+59,0,0
+60,0,0
+61,0,0
+62,0,0
+63,0,0
+64,0,0
+65,0,0
+66,0,0
+67,0,0
+68,0,0
+69,0,0
+70,0,0
\ No newline at end of file
diff --git a/GEMstack/knowledge/routes/turn_right.csv b/GEMstack/knowledge/routes/turn_right.csv
new file mode 100644
index 000000000..7ec523657
--- /dev/null
+++ b/GEMstack/knowledge/routes/turn_right.csv
@@ -0,0 +1,21 @@
+0,0,0
+1,0,0
+2,0,0
+3,0,0
+4,0,0
+5,0,0
+6,0,0
+7,0,0
+8,0,0
+9,0,0
+10,0,0
+10,-1,0
+10,-2,0
+10,-3,0
+10,-4,0
+10,-5,0
+10,-6,0
+10,-7,0
+10,-8,0
+10,-9,0
+10,-10,0
diff --git a/GEMstack/knowledge/routes/turn_right2.csv b/GEMstack/knowledge/routes/turn_right2.csv
new file mode 100644
index 000000000..f8ae9b5df
--- /dev/null
+++ b/GEMstack/knowledge/routes/turn_right2.csv
@@ -0,0 +1,28 @@
+0,0,0
+1,0,0
+2,0,0
+3,0,0
+4,0,0
+5,0,0
+6,0,0
+7,0,0
+8,0,0
+9,0,0
+11,-.1,0
+12,-.5,0
+13,-1,0
+14,-2,0
+14.5,-2.8,0
+14.75,-3.5,0
+14.9,-4,0
+15,-5,0
+15,-6,0
+15,-7,0
+15,-8,0
+15,-9,0
+15,-10,0
+15,-11,0
+15,-12,0
+15,-13,0
+15,-14,0
+15,-16,0
diff --git a/GEMstack/knowledge/routes/turn_right_wider.csv b/GEMstack/knowledge/routes/turn_right_wider.csv
new file mode 100644
index 000000000..0041e35f7
--- /dev/null
+++ b/GEMstack/knowledge/routes/turn_right_wider.csv
@@ -0,0 +1,34 @@
+0,0,0
+1,0,0
+2,0,0
+3,0,0
+4,0,0
+5,0,0
+6,0,0
+7,0,0
+8,0,0
+9,0,0
+10,0,0
+11,-.06,0
+12,-.2,0
+13,-.5,0
+14,-.85,0
+15,-1.4,0
+16,-2,0
+17,-2.85,0
+18,-4,0
+19,-5.7,0
+19.5,-6.9,0
+19.75,-7.8,0
+19.95,-9,0
+20,-10,0
+20,-11,0
+20,-12,0
+20,-13,0
+20,-14,0
+20,-15,0
+20,-16,0
+20,-17,0
+20,-18,0
+20,-19,0
+20,-20,0
\ No newline at end of file
diff --git a/GEMstack/knowledge/vehicle/dynamics.py b/GEMstack/knowledge/vehicle/dynamics.py
index 9bd33a92e..3e097f4fc 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_e2_fast_limits.yaml b/GEMstack/knowledge/vehicle/gem_e2_fast_limits.yaml
index 59150d0c3..ccd374398 100644
--- a/GEMstack/knowledge/vehicle/gem_e2_fast_limits.yaml
+++ b/GEMstack/knowledge/vehicle/gem_e2_fast_limits.yaml
@@ -5,4 +5,6 @@ max_acceleration: 3.0 #m/s^2
max_deceleration: 5.0 #m/s^2
max_accelerator_pedal: 1.0 #0-1
max_brake_pedal: 1.0 #0-1
-
+max_longitudinal_acceleration: 2.07 #m/s^2 e4
+min_longitudinal_acceleration: -2.61 #m/s^2 deceleration 2.61 e4
+max_lateral_acceleration: 3.3 #m/s^2 e4
diff --git a/GEMstack/knowledge/vehicle/gem_e4.yaml b/GEMstack/knowledge/vehicle/gem_e4.yaml
index 78785ab03..23208868f 100644
--- a/GEMstack/knowledge/vehicle/gem_e4.yaml
+++ b/GEMstack/knowledge/vehicle/gem_e4.yaml
@@ -7,7 +7,7 @@ max_command_rate : 10.0 #for hardware, max rate of commands to send to
#using !include directives helps maintain reuse of common settings
geometry: !include gem_e4_geometry.yaml
dynamics: !include gem_e4_dynamics.yaml
-limits: !include gem_e2_slow_limits.yaml
+limits: !include gem_e2_fast_limits.yaml
control_defaults: !include gem_e2_control_defaults.yaml
calibration: !include ../calibration/gem_e4.yaml
sensors: !include gem_e4_sensor_environment.yaml
diff --git a/GEMstack/knowledge/vehicle/gem_e4_dynamics.yaml b/GEMstack/knowledge/vehicle/gem_e4_dynamics.yaml
index d20d2c357..23712b0a5 100644
--- a/GEMstack/knowledge/vehicle/gem_e4_dynamics.yaml
+++ b/GEMstack/knowledge/vehicle/gem_e4_dynamics.yaml
@@ -1,22 +1,24 @@
-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
+acceleration_model : hang_v1
accelerator_active_range : [0.2, 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.5,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)
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 a0c611b37..af509af66 100644
--- a/GEMstack/knowledge/vehicle/gem_e4_sensor_environment.yaml
+++ b/GEMstack/knowledge/vehicle/gem_e4_sensor_environment.yaml
@@ -3,4 +3,4 @@ ros_topics:
front_camera: /oak/rgb/image_raw
front_depth: /oak/stereo/image_raw
gnss: /septentrio_gnss/insnavgeod
-
\ No newline at end of file
+
diff --git a/GEMstack/mathutils/quadratic_equation.py b/GEMstack/mathutils/quadratic_equation.py
new file mode 100644
index 000000000..6580fbec9
--- /dev/null
+++ b/GEMstack/mathutils/quadratic_equation.py
@@ -0,0 +1,21 @@
+import math
+
+def quad_root(a : float, b : float, c : float) -> float:
+ """Calculates the roots of a quadratic equation
+
+ Args:
+ a (float): coefficient of x^2
+ b (float): coefficient of x
+ c (float): constant term
+
+ Returns:
+ float: returns all valid roots of the quadratic equation
+ """
+ x1 = (-b + max(0,(b**2 - 4*a*c))**0.5)/(2*a)
+ x2 = (-b - max(0,(b**2 - 4*a*c))**0.5)/(2*a)
+
+ if math.isnan(x1): x1 = 0
+ if math.isnan(x2): x2 = 0
+
+ valid_roots = [n for n in [x1, x2] if not type(n) is complex]
+ return valid_roots
\ No newline at end of file
diff --git a/GEMstack/mathutils/transforms.py b/GEMstack/mathutils/transforms.py
index a29ec48e2..89e5b58b5 100644
--- a/GEMstack/mathutils/transforms.py
+++ b/GEMstack/mathutils/transforms.py
@@ -117,7 +117,7 @@ def lat_lon_to_xy(lat : float, lon : float, lat_reference : float, lon_reference
Returns (x,y), where x is east in m, y is north in m.
"""
- import alvinxy.alvinxy as axy
+ import alvinxy.alvinxy as axy
# convert GNSS waypoints into local fixed frame reprented in x and y
east_x, north_y = axy.ll2xy(lat, lon, lat_reference, lon_reference)
return east_x, north_y
diff --git a/GEMstack/offboard/calibration/README.md b/GEMstack/offboard/calibration/README.md
new file mode 100644
index 000000000..c804f7a7d
--- /dev/null
+++ b/GEMstack/offboard/calibration/README.md
@@ -0,0 +1,158 @@
+# Data Capture
+
+### Data Capture Script (`capture_ouster_oak.py`)
+
+Set up on vehicle:
+
+1. Run roscore in a terminal
+2. Run catkin_make in gem stack
+3. Run source /demo_ws/devel/setup.bash
+4. Run roslaunch basic_launch sensor_init.launch to get all sensors running
+
+Default script usage:
+
+ python3 capture_ouster_oak.py
+
+Additional Options:
+1. To specify directory to save data, use --folder "path to save location" (default save folder is data)
+2. To specify frequency of data capture, use --frequency put_frequency_in_hz_here (default is 2 hz)
+3. To specify the what index the data should start being saved as, use --start_index desired_index_here (default is 1)
+
+
+# GEMstack Offboard Calibration
+
+This section explains tools for offline calibration of LiDAR and camera sensors to the vehicle coordinate system on the GEM E4 platform. The calibration pipeline consists of three stages:
+
+1. **LiDAR-to-Vehicle**
+2. **Camera-to-Vehicle**
+3. **LiDAR-to-Camera**
+
+## Dependencies
+
+```
+pip install opencv-python scipy numpy matplotlib argparse pyyaml pyvis
+
+# If getting some issues, try:
+pip install trame ipywidgets trame-vuetify
+```
+
+---
+
+
+## Calibration Pipeline
+
+### 1. LiDAR-to-Vehicle Calibration (`lidar_to_vehicle.py`)
+**Method**:
+- **Ground Plane Detection**:
+ 1. Crop LiDAR points near ground (Z ∈ [-3, -2])
+ 2. Use RANSAC to fit a plane to ground points
+ 3. Compute vehicle height (`tz`) using plane equation and axel height offset (0.2794m)
+ 4. Derive pitch (`rx`) and roll (`ry`) from plane normal vector
+
+- **Frontal Object Alignment**:
+ 1. Crop LiDAR data to frontal area (X ∈ [0,20], Y ∈ [-1,1])
+ 2. Fit line to object points for yaw (`rz`) estimation
+ 3. Compute translation (`tx`, `ty`) using vehicle dimensions
+
+**Usage**:
+
+Our script assumes data is formated as: colorx.png, lidarx.npz, depthx.tif where x is some index number. x is chosen using the --index flag seen below. Set it based on what data sample you want to use for calibration.
+
+ python3 lidar_to_vehicle.py --data_path "path to data folder" --index INDEX_NUM
+
+Optionally, use --vis flag for visualizations throughout the computation process
+
+
+### 2. CAMERA-to-Vehicle Calibration (`camera_to_vehicle_manual.py`)
+**Method**:
+ 1. Capture camera intrinsics using camera_info.py (ROS node)
+ 2. Manually select 8 matching points in RGB image and LiDAR cloud (can adjust variable to select more pairs)
+ 3. Solve PnP problem to compute camera extrinsics
+
+**Usage**:
+ 1. Get camera intrinsics:
+ rosrun offboard\calibration\camera_info.py # Prints intrinsic matrix
+ 2. Update camera_in in script with intrinsics
+ 3. Our script assumes data is formated as: colorx.png, lidarx.npz, depthx.tif where x is some index number. x is chosen using the --index flag seen below. Set it based on what data sample you want to use for calibration.
+
+ The script also reads the lidar_to_vehicle matrix from the gem_e4_ouster.yaml file so ensure that is up to date.
+
+ 4. Run calibration:
+
+ python3 camera_to_vehicle_manual.py --data_path "path to data folder" --index INDEX_NUM --config "path to gem_e4_ouster.yaml"
+
+ 5. There will be a pop-up of the rgb image depending on the data index you chose. Left click and select as many points as manually specified in the script.
+ 6. The window will automatically close and reveal a pop-up of the lidar point cloud.
+ 7. Choose the corresponding lidar points with hovering over the point and right-clicking, or pressing P
+ 8. Once selected all corresponding points, close the window and the output will be printed.
+
+### 3. LIDAR-to-CAMERA Calibration (`lidar_to_camera.py`)
+**Method**:
+ 1. Invert Camera-to-Vehicle matrix
+ 2. Multiply with LiDAR-to-Vehicle matrix
+
+**Usage**:
+```
+python3 lidar_to_camera.py # Ensure T_lidar_vehicle and T_camera_vehicle matrices are updated
+```
+
+### Visualization Tools
+
+**3D Alignment Check**:
+ 1. Use vis() function in scripts to view calibrated LiDAR/camera clouds
+ 2. Use --vis flag when running lidar_to_vehicle.py for ground plane/object visualization
+ 3. Use test_transforms.py to visualize the transformed lidar point cloud to camera frame on top of the corresponding png image. Helps verify accuracy of lidar->camera.
+
+Usage of test_transforms.py:
+```
+python3 test_transforms.py --data_path "path to data folder" --index INDEX_NUM
+```
+Data path is the directory where lidar npz and color png files are located, index number is whichever lidar/png pair you want to evaluate. Ex. lidar1.npz color1.png where INDEX_NUM is 1 (--index 1)
+
+**Projection Validation**:
+ 1. RGB image overlaid with transformed LiDAR points (Z-buffered)
+ 2. Frontal view comparison of camera and LiDAR data
+
+
+
+
+
+
+### Assumption and Notes
+
+1. The sensor data should be time-aligned.
+2. The flat surface should be detectable in the Lidar scan
+3. Magic Numbers:
+ Axel height (0.2794m) from physical measurements
+ Frontal crop areas based on vehicle dimensions
+4. Validation: Use pyvista visualizations to verify alignment
+
+
+### Results
+
+Our resultant transformation matrices are the following:
+```
+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.000000000, 0.00000000, 0.00000000, 1.0]])
+
+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.000000000, 0.00000000, 0,00000000, 1.0]])
+
+T_lidar_camera = 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]
+ ])
+```
+We find that these matrices are very accurate and worked well with perceptions task of identifying pedestrains using camera and lidar. Perception team makes use of our lidar->camera matrix. Below is an image showcasing the effectiveness of our lidar->camera matrix. You can see the lidar pointcloud corresponds very well to the pixels in the image.
+
+
+
+We calculate this lidar->camera matrix by doing a matrix multiplication between the inverted camera->vehicle matrix and lidar->vehicle matrix. To evaluate the effectiveness of both of these matrices individually, we use visualizations in their respective calculations scripts.
+
+For basic sanity check purposes, we also ensure that the determinant of the rotation matrices we get is 1.
diff --git a/GEMstack/offboard/calibration/camera_info.py b/GEMstack/offboard/calibration/camera_info.py
new file mode 100644
index 000000000..5610efb7f
--- /dev/null
+++ b/GEMstack/offboard/calibration/camera_info.py
@@ -0,0 +1,41 @@
+# ROS Headers
+import rospy
+from sensor_msgs.msg import Image,PointCloud2, CameraInfo
+import sensor_msgs.point_cloud2 as pc2
+import ctypes
+import struct
+import pickle
+import image_geometry
+
+import numpy as np
+import os
+import time
+
+camera_image = None
+
+def camera_callback(info : CameraInfo):
+ global camera_image
+ camera_image = info
+
+def get_intrinsics():
+ model = image_geometry.PinholeCameraModel()
+ model.fromCameraInfo(camera_image)
+ print(model.intrinsicMatrix())
+
+def main(folder='data',start_index=1):
+ rospy.init_node("capture_cam_info",disable_signals=True)
+ caminfo_sub = rospy.Subscriber("/oak/rgb/camera_info", CameraInfo, camera_callback)
+ while True:
+ if camera_image:
+ time.sleep(1)
+ get_intrinsics()
+
+if __name__ == '__main__':
+ import sys
+ folder = 'data'
+ start_index = 1
+ if len(sys.argv) >= 2:
+ folder = sys.argv[1]
+ if len(sys.argv) >= 3:
+ start_index = int(sys.argv[2])
+ main(folder,start_index)
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/capture_ouster_oak.py b/GEMstack/offboard/calibration/capture_ouster_oak.py
new file mode 100644
index 000000000..d20b38b57
--- /dev/null
+++ b/GEMstack/offboard/calibration/capture_ouster_oak.py
@@ -0,0 +1,103 @@
+# ROS Headers
+import rospy
+from sensor_msgs.msg import Image,PointCloud2
+import sensor_msgs.point_cloud2 as pc2
+import ctypes
+import struct
+import argparse
+
+
+# OpenCV and cv2 bridge
+import cv2
+from cv_bridge import CvBridge
+import numpy as np
+import os
+import time
+
+lidar_points = None
+camera_image = None
+depth = None
+depth_image = None
+bridge = CvBridge()
+
+def lidar_callback(lidar : PointCloud2):
+ global lidar_points
+ lidar_points = lidar
+
+def camera_callback(img : Image):
+ global camera_image
+ camera_image = img
+
+def depth_callback(img : Image):
+ global depth_image
+ depth_image = img
+
+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)
+ 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
+ b = (pack & 0x000000FF)
+ #r,g,b values in the 0-255 range
+ xyzrgb[i,3:] = (r,g,b)
+ return xyzrgb
+ else:
+ 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)
+
+ pc = pc2_to_numpy(lidar_points,want_rgb=False) # convert lidar feed to numpy
+ 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))
+ dimage = dimage.astype(np.uint16)
+ cv2.imwrite(depth_fn,dimage)
+
+def main(folder='data',start_index=1, frequency=2):
+ rospy.init_node("capture_ouster_oak",disable_signals=True)
+ lidar_sub = rospy.Subscriber("/ouster/points", PointCloud2, lidar_callback)
+ camera_sub = rospy.Subscriber("/oak/rgb/image_raw", Image, camera_callback)
+ depth_sub = rospy.Subscriber("/oak/stereo/image_raw", Image, depth_callback)
+ index = start_index
+ print(" Storing lidar point clouds as npz")
+ print(" Storing color images as png")
+ print(" Storing depth images as tif")
+ print(" Ctrl+C to quit")
+ while True:
+ if camera_image and depth_image:
+ cv2.imshow("result",bridge.imgmsg_to_cv2(camera_image))
+ time.sleep(1.0/frequency)
+ 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))]
+ save_scan(*files)
+ index += 1
+
+if __name__ == '__main__':
+ import sys
+ parser = argparse.ArgumentParser(description='Capture LiDAR and camera data.')
+ parser.add_argument('--folder', type=str, default='data', help='Directory to store data')
+ parser.add_argument('--start_index', type=int, default=1, help='Starting index for saved files')
+ parser.add_argument('--frequency', type=float, default=2.0, help='Capture frequency in Hz')
+ args = parser.parse_args()
+ main(args.folder, args.start_index, args.frequency)
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
new file mode 100644
index 000000000..07fe0f7c4
--- /dev/null
+++ b/GEMstack/offboard/calibration/test_transforms.py
@@ -0,0 +1,74 @@
+import numpy as np
+import cv2
+import matplotlib.pyplot as plt
+import argparse
+import os
+
+def load_lidar_data(data_folder, index):
+ lidar_path = os.path.join(data_folder, f"lidar{index}.npz")
+ lidar_data = np.load(lidar_path)
+ return lidar_data['arr_0']
+
+def load_image(data_folder, index):
+ image_path = os.path.join(data_folder, f"color{index}.png")
+ image = cv2.imread(image_path)
+ return cv2.cvtColor(image, cv2.COLOR_BGR2RGB)
+
+def main(data_folder, index):
+ # Load Data
+ lidar_points = load_lidar_data(data_folder, index)
+ image = load_image(data_folder, index)
+
+ # Transformation Matrix
+ T_lidar_camera = 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]
+ ])
+
+ # Convert LiDAR points to homogeneous coordinates
+ num_points = lidar_points.shape[0]
+ lidar_homogeneous = np.hstack((lidar_points, np.ones((num_points, 1))))
+
+ # Transform LiDAR points to Camera Frame
+ lidar_points_camera = (T_lidar_camera @ lidar_homogeneous.T).T
+
+ # Intrinsic Camera Matrix
+ K = np.array([
+ [684.83331299, 0. , 573.37109375],
+ [ 0. , 684.60968018, 363.70092773],
+ [ 0. , 0. , 1. ]
+ ], dtype=np.float32)
+
+ # Extract 3D points in camera frame
+ X_c = lidar_points_camera[:, 0]
+ Y_c =lidar_points_camera[:, 1]
+ Z_c = lidar_points_camera[:, 2] #depth
+
+ # Avoid division by zero
+ valid = Z_c > 0
+ X_c, Y_c, Z_c = X_c[valid], Y_c[valid], Z_c[valid]
+
+ # Project points onto image plane
+ u = (K[0, 0] * X_c / Z_c) + K[0, 2]
+ v = (K[1, 1] * Y_c / Z_c) + K[1, 2]
+
+ # Filter points within image bounds
+ img_h, img_w, _ = image.shape
+ valid_pts = (u >= 0) & (u < img_w) & (v >= 0) & (v < img_h)
+ u, v = u[valid_pts], v[valid_pts]
+
+ # Plot projected points on camera image
+ plt.imshow(image)
+ plt.scatter(u, v, s=2, c='r')
+ plt.title("Projected LiDAR Points on Camera Image")
+ plt.show()
+
+if __name__ == "__main__":
+ parser = argparse.ArgumentParser(description="Project LiDAR points onto a camera image.")
+ parser.add_argument("--data_folder", type=str, required=True, help="Path to the data folder")
+ parser.add_argument("--index", type=int, required=True, help="Index of the dataset (e.g., 1 for color1.png and lidar1.npz)")
+ args = parser.parse_args()
+
+ main(args.data_folder, args.index)
\ No newline at end of file
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/offboard/log_management/s3.py b/GEMstack/offboard/log_management/s3.py
new file mode 100644
index 000000000..b8f2ea4c8
--- /dev/null
+++ b/GEMstack/offboard/log_management/s3.py
@@ -0,0 +1,248 @@
+#!/usr/bin/env python3
+"""
+This client interacts with S3 to upload (push) or download (pull) the latest folder.
+For push, the latest folder in the local base directory (default "logs")
+is determined based on its timestamp (folder name in "YYYY-MM-DD_HH-MM-SS" format).
+For pull, the latest folder under the S3 prefix is selected.
+
+Before running this client make sure you have defined .env in root with following values:
+AWS_ACCESS_KEY_ID=example
+AWS_SECRET_ACCESS_KEY=example
+AWS_DEFAULT_REGION=us-east-1
+
+Requires:
+ pip install boto3 python-dotenv
+
+Example Usage:
+
+ # Push the latest folder from the local "logs" directory to S3:
+ python3 -m GEMstack.offboard.log_management.s3 \
+ --action push \
+ --bucket cs588 \
+ --s3-prefix captures
+
+ # Pull (download) the latest folder from S3 into local "download/" directory:
+ python3 -m GEMstack.offboard.log_management.s3 \
+ --action pull \
+ --bucket cs588 \
+ --s3-prefix captures \
+ --dest-dir download
+"""
+
+import argparse
+import boto3
+import os
+import sys
+from datetime import datetime
+from dotenv import load_dotenv
+
+def get_s3_client():
+ """
+ Initializes the S3 client using AWS credentials from environment variables.
+ Expects:
+ - AWS_ACCESS_KEY_ID
+ - AWS_SECRET_ACCESS_KEY
+ - AWS_DEFAULT_REGION
+ Exits if any of these are missing.
+ """
+ # load environment variables from .env file (override local config if exists)
+ load_dotenv(override=True)
+
+ access_key = os.environ.get('AWS_ACCESS_KEY_ID')
+ secret_key = os.environ.get('AWS_SECRET_ACCESS_KEY')
+ region = os.environ.get('AWS_DEFAULT_REGION')
+
+ if not access_key or not secret_key or not region:
+ sys.exit(
+ "Error: AWS credentials not set. Please set AWS_ACCESS_KEY_ID, "
+ "AWS_SECRET_ACCESS_KEY, and AWS_DEFAULT_REGION environment variables (in .env)."
+ )
+
+ return boto3.client(
+ 's3',
+ aws_access_key_id=access_key,
+ aws_secret_access_key=secret_key,
+ region_name=region
+ )
+
+def check_s3_connection(s3_client, bucket):
+ """
+ Verifies that we can connect to S3 and access the specified bucket.
+ """
+ try:
+ s3_client.head_bucket(Bucket=bucket)
+ print(f"Connection check: Successfully accessed bucket '{bucket}'")
+ except Exception as e:
+ sys.exit(f"Error: Could not connect to S3 bucket '{bucket}': {e}")
+
+def push_folder_to_s3(folder_path, bucket, s3_prefix):
+ """
+ Walks through the folder and uploads each file to S3 under the given prefix.
+ Files are stored under the key: s3_prefix/folder_name/.
+ """
+ s3_client = get_s3_client()
+ check_s3_connection(s3_client, bucket)
+
+ folder_name = os.path.basename(folder_path)
+ files_uploaded = 0
+
+ for root, _, files in os.walk(folder_path):
+ for file in files:
+ local_path = os.path.join(root, file)
+ # determine the file's path relative to the folder being pushed.
+ relative_path = os.path.relpath(local_path, folder_path)
+ s3_key = os.path.join(s3_prefix, folder_name, relative_path)
+ try:
+ print(f"Uploading {local_path} to s3://{bucket}/{s3_key}")
+ s3_client.upload_file(local_path, bucket, s3_key)
+ files_uploaded += 1
+ except Exception as e:
+ print(f"Error uploading {local_path}: {e}")
+
+ if files_uploaded == 0:
+ sys.exit(f"Error: No files were uploaded from folder: {folder_path}")
+
+def pull_folder_from_s3(bucket, s3_prefix, folder_name, dest_dir):
+ """
+ Downloads all objects from S3 whose key begins with s3_prefix/folder_name.
+ The folder will be recreated under `dest_dir/folder_name`.
+ """
+ s3_client = get_s3_client()
+ check_s3_connection(s3_client, bucket)
+
+ prefix = os.path.join(s3_prefix, folder_name)
+
+ paginator = s3_client.get_paginator('list_objects_v2')
+ pages = paginator.paginate(Bucket=bucket, Prefix=prefix)
+
+ found_files = False
+ for page in pages:
+ if 'Contents' not in page:
+ continue
+ for obj in page['Contents']:
+ key = obj['Key']
+ if key.endswith("/"):
+ continue
+
+ found_files = True
+ relative_path = os.path.relpath(key, prefix)
+ local_path = os.path.join(dest_dir, folder_name, relative_path)
+
+ os.makedirs(os.path.dirname(local_path), exist_ok=True)
+
+ print(f"Downloading s3://{bucket}/{key} to {local_path}")
+ try:
+ s3_client.download_file(bucket, key, local_path)
+ except Exception as e:
+ print(f"Error downloading s3://{bucket}/{key}: {e}")
+
+ if not found_files:
+ sys.exit(f"Error: No files found in bucket '{bucket}' with prefix '{prefix}'")
+
+def get_latest_local_folder(base_dir):
+ """
+ Scans the base directory for subdirectories and returns the one with the latest timestamp.
+ Assumes folder names are in the format "YYYY-MM-DD_HH-MM-SS".
+ """
+ try:
+ subdirs = [d for d in os.listdir(base_dir) if os.path.isdir(os.path.join(base_dir, d))]
+ except FileNotFoundError:
+ sys.exit(f"Error: Base directory does not exist: {base_dir}")
+
+ if not subdirs:
+ sys.exit(f"Error: No subdirectories found in base directory: {base_dir}")
+
+ def parse_timestamp(folder):
+ try:
+ return datetime.strptime(folder, "%Y-%m-%d_%H-%M-%S")
+ except Exception:
+ return datetime.min
+
+ latest = sorted(subdirs, key=parse_timestamp)[-1]
+ return latest
+
+def get_latest_s3_folder(s3_client, bucket, s3_prefix):
+ """
+ Retrieves the latest folder name from S3 under the given prefix.
+ It lists common prefixes (folders) and returns the one with the latest timestamp.
+ Assumes folder names follow the format "YYYY-MM-DD_HH-MM-SS".
+ """
+ response = s3_client.list_objects_v2(
+ Bucket=bucket,
+ Prefix=s3_prefix + "/",
+ Delimiter="/"
+ )
+ if 'CommonPrefixes' not in response:
+ sys.exit(f"Error: No folders found in S3 bucket '{bucket}' with prefix '{s3_prefix}'")
+
+ folders = []
+ for cp in response['CommonPrefixes']:
+ prefix = cp.get('Prefix')
+ # Expect prefix like "captures/2025-02-12_15-30-00/"
+ parts = prefix.split('/')
+ if len(parts) >= 2:
+ folder_name = parts[-2]
+ folders.append(folder_name)
+
+ if not folders:
+ sys.exit(f"Error: No valid folder names found in S3 bucket '{bucket}' with prefix '{s3_prefix}'")
+
+ def parse_timestamp(folder):
+ try:
+ return datetime.strptime(folder, "%Y-%m-%d_%H-%M-%S")
+ except Exception:
+ return datetime.min
+
+ latest = sorted(folders, key=parse_timestamp)[-1]
+ return latest
+
+def main():
+ parser = argparse.ArgumentParser(
+ description="Push or pull the latest folder to/from an S3 bucket."
+ )
+ parser.add_argument("--action", choices=["push", "pull"], required=True,
+ help="Choose whether to push (upload) or pull (download) a folder.")
+ # The --folder argument is now optional. If not provided, the latest folder is auto-detected.
+ parser.add_argument("--folder", default=None,
+ help="(Optional) Folder name (e.g. 2025-02-12_15-30-00). If omitted, the latest folder is selected.")
+ parser.add_argument("--base-dir", default="logs",
+ help="Local base directory where capture runs are stored (used for push).")
+ parser.add_argument("--dest-dir", default="download",
+ help="Local directory to place the downloaded folder (used for pull).")
+ parser.add_argument("--bucket", required=True,
+ help="S3 bucket name.")
+ parser.add_argument("--s3-prefix", default="captures",
+ help="S3 prefix (folder) where data is stored or will be uploaded.")
+ args = parser.parse_args()
+
+ if args.action == "push":
+ # If no folder is provided, determine the latest local folder from the base directory.
+ if args.folder is None:
+ args.folder = get_latest_local_folder(args.base_dir)
+ print(f"Auto-detected latest local folder: {args.folder}")
+ folder_path = os.path.join(args.base_dir, args.folder)
+ if not os.path.exists(folder_path):
+ sys.exit(f"Error: Folder does not exist: {folder_path}")
+
+ # check if the folder is empty.
+ folder_empty = True
+ for _, _, files in os.walk(folder_path):
+ if files:
+ folder_empty = False
+ break
+ if folder_empty:
+ sys.exit(f"Error: Folder is empty: {folder_path}")
+
+ push_folder_to_s3(folder_path, args.bucket, args.s3_prefix)
+
+ elif args.action == "pull":
+ # If no folder is provided, query S3 for the latest folder under the specified prefix.
+ if args.folder is None:
+ s3_client = get_s3_client()
+ check_s3_connection(s3_client, args.bucket)
+ args.folder = get_latest_s3_folder(s3_client, args.bucket, args.s3_prefix)
+ print(f"Auto-detected latest folder on S3: {args.folder}")
+ pull_folder_from_s3(args.bucket, args.s3_prefix, args.folder, args.dest_dir)
+
+if __name__ == '__main__':
+ main()
diff --git a/GEMstack/onboard/execution/entrypoint.py b/GEMstack/onboard/execution/entrypoint.py
index b1e7a8d10..f20621bbd 100644
--- a/GEMstack/onboard/execution/entrypoint.py
+++ b/GEMstack/onboard/execution/entrypoint.py
@@ -122,17 +122,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.py b/GEMstack/onboard/interface/gem.py
index 9abcd1b6b..0b3e09b6a 100644
--- a/GEMstack/onboard/interface/gem.py
+++ b/GEMstack/onboard/interface/gem.py
@@ -4,6 +4,7 @@
from ...knowledge.vehicle.geometry import front2steer,steer2front,heading_rate
from ...knowledge.vehicle.dynamics import pedal_positions_to_acceleration, acceleration_to_pedal_positions
from typing import List,Optional,Callable
+import numpy as np
@dataclass
@serialization.register
@@ -95,6 +96,7 @@ class GEMInterface:
def __init__(self):
self.last_command = None # type: GEMVehicleCommand
self.last_reading = None # type: GEMVehicleReading
+ self.max_accel = settings.get('vehicle.limits.max_accelerator_pedal')
def start(self):
pass
@@ -133,7 +135,7 @@ def hardware_faults(self) -> List[str]:
"""
raise NotImplementedError()
- def simple_command(self, acceleration_mps2 : float, steering_wheel_angle : float, state : VehicleState = None) -> GEMVehicleCommand:
+ def simple_command(self, acceleration_mps2: float, steering_wheel_angle: float, state: VehicleState = None) -> GEMVehicleCommand:
""""
Returns a command according to a desired acceleration and steering angle
@@ -145,7 +147,11 @@ def simple_command(self, acceleration_mps2 : float, steering_wheel_angle : float
pitch = state.pose.pitch if state is not None and state.pose.pitch is not None else 0.0
v = state.v if state is not None else 0.0
gear = state.gear if state is not None else 1
- acc_pos,brake_pos,gear = acceleration_to_pedal_positions(acceleration_mps2, v, pitch, gear)
+
+ acc_pos, brake_pos, gear = acceleration_to_pedal_positions(acceleration_mps2, v, pitch, gear)
+
+
+ # acc_pos,brake_pos,gear = acceleration_to_pedal_positions(acceleration_mps2, v, pitch, gear)
cmd = GEMVehicleCommand(gear=gear,
accelerator_pedal_position=acc_pos,
diff --git a/GEMstack/onboard/interface/gem_hardware.py b/GEMstack/onboard/interface/gem_hardware.py
index 836d7ef71..21cac6fd1 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):
@@ -187,6 +188,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)
@@ -294,6 +296,16 @@ def send_command(self, command : GEMVehicleCommand):
if command.brake_pedal_position > 0.0:
self.accel_cmd.f64_cmd = 0.0
self.brake_cmd.f64_cmd = command.brake_pedal_position
+
+ # if self.last_reading.speed == 0 and command.brake_pedal_position > 0.0 and command.accelerator_pedal_position > 0.0:
+ # self.accel_cmd.f64_cmd = command.accelerator_pedal_position
+ # self.brake_cmd.f64_cmd = command.brake_pedal_position
+ # else:
+ # self.accel_cmd.f64_cmd = command.accelerator_pedal_position
+ # if command.brake_pedal_position > 0.0:
+ # self.accel_cmd.f64_cmd = 0.0
+ # self.brake_cmd.f64_cmd = command.brake_pedal_position
+
self.steer_cmd.angular_position = command.steering_wheel_angle
self.steer_cmd.angular_velocity_limit = command.steering_wheel_speed
print("**************************")
@@ -305,7 +317,7 @@ def send_command(self, command : GEMVehicleCommand):
print("Warning: commanded acceleration exceeded accel pedal limit")
self.accel_cmd.f64_cmd = maxacc
if self.brake_cmd.f64_cmd > maxbrake:
- print("Warning: commanded braking exceeded brake pedal limit")
+ print("Warning: commanded braking exceed 0 # to ed brake pedal limit")
self.brake_cmd.f64_cmd = maxbrake
print("**************************")
@@ -317,6 +329,7 @@ def send_command(self, command : GEMVehicleCommand):
self.accel_cmd.clear = False
self.accel_cmd.ignore = False
+
self.gear_cmd.ui16_cmd = PacmodCmd.SHIFT_FORWARD
self.gear_cmd.enable = True
self.gear_pub.publish(self.gear_cmd)
diff --git a/GEMstack/onboard/interface/gem_simulator.py b/GEMstack/onboard/interface/gem_simulator.py
index 2abfde71f..88adf8433 100644
--- a/GEMstack/onboard/interface/gem_simulator.py
+++ b/GEMstack/onboard/interface/gem_simulator.py
@@ -19,7 +19,8 @@
'bicyclist' : (1.8,0.5,1.6),
'car' : (4.0,2.5,1.4),
'medium_truck': (6.0,2.5,3.0),
- 'large_truck': (10.0,2.5,3.5)
+ 'large_truck': (10.0,2.5,3.5),
+ 'cone' : (0.5,0.5,1.0)
}
AGENT_TYPE_TO_ENUM = {
@@ -27,7 +28,8 @@
'bicyclist' : AgentEnum.BICYCLIST,
'car' : AgentEnum.CAR,
'medium_truck': AgentEnum.MEDIUM_TRUCK,
- 'large_truck': AgentEnum.LARGE_TRUCK
+ 'large_truck': AgentEnum.LARGE_TRUCK,
+ 'cone': AgentEnum.CONE
}
AGENT_NOMINAL_VELOCITY = {
@@ -35,7 +37,8 @@
'bicyclist' : 5.0,
'car' : 20.0,
'medium_truck': 15.0,
- 'large_truck': 10.0
+ 'large_truck': 10.0,
+ 'cone' : 0.0
}
AGENT_NOMINAL_ACCELERATION = {
@@ -43,7 +46,8 @@
'bicyclist' : 2.0,
'car' : 5.0,
'medium_truck': 3.0,
- 'large_truck': 2.0
+ 'large_truck': 2.0,
+ 'cone' : 0.0
}
class AgentSimulation:
@@ -207,7 +211,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/cone_detection.py b/GEMstack/onboard/perception/cone_detection.py
new file mode 100644
index 000000000..42ea26169
--- /dev/null
+++ b/GEMstack/onboard/perception/cone_detection.py
@@ -0,0 +1,516 @@
+from ...state import AllState, VehicleState, ObjectPose, ObjectFrameEnum, AgentState, AgentEnum, AgentActivityEnum
+from ..interface.gem import GEMInterface
+from ..component import Component
+from .perception_utils import *
+from ultralytics import YOLO
+import cv2
+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 ConeDetector3D(Component):
+ """
+ Detects cones by fusing YOLO 2D detections with LiDAR point cloud data.
+
+ Tracking is optional: set `enable_tracking=False` to disable persistent tracking
+ and return only detections from the current frame.
+
+ Supports multiple cameras; each camera’s intrinsics and extrinsics are
+ loaded from a single YAML calibration file via plain PyYAML.
+ """
+
+ 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,
+ orientation: bool = True,
+ use_start_frame: bool = True,
+ **kwargs
+ ):
+ # Core interfaces and state
+ self.vehicle_interface = vehicle_interface
+ self.current_agents = {}
+ self.tracked_agents = {}
+ self.cone_counter = 0
+ self.latest_image = None
+ self.latest_lidar = None
+ self.bridge = CvBridge()
+ self.start_pose_abs = None
+ self.start_time = None
+
+ # Config flags
+ 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.orientation = orientation
+ self.use_start_frame = use_start_frame
+
+ # 1) Load lidar→vehicle transform
+ if T_l2v is not None:
+ self.T_l2v = np.array(T_l2v)
+ else:
+ 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 the supplied 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'][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'])
+
+ # Derived transforms
+
+ self.undistort_map1 = None
+ self.undistort_map2 = None
+ self.camera_front = (camera_name=='front')
+
+ def rate(self) -> float:
+ return 8
+
+ def state_inputs(self) -> list:
+ return ['vehicle']
+
+ def state_outputs(self) -> list:
+ return ['agents']
+
+ def initialize(self):
+ # --- 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'
+ )
+
+ # 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=500, slop=0.05)
+ self.sync.registerCallback(self.synchronized_callback)
+
+ # Initialize the YOLO detector
+ self.detector = YOLO('GEMstack/knowledge/detection/cone.pt')
+ self.detector.to('cuda')
+ 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):
+ step1 = time.time()
+ try:
+ self.latest_image = self.bridge.imgmsg_to_cv2(image_msg, "bgr8")
+ except Exception as e:
+ rospy.logerr("Failed to convert image: {}".format(e))
+ self.latest_image = None
+ step2 = time.time()
+ self.latest_lidar = pc2_to_numpy(lidar_msg, want_rgb=False)
+ step3 = time.time()
+ # print('image callback: ', step2 - step1, 'lidar callback ', step3 - step2)
+
+ 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 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
+
+ def update(self, vehicle: VehicleState) -> Dict[str, AgentState]:
+ downsample = False
+ # Gate guards against data not being present for both sensors:
+ if self.latest_image is None or self.latest_lidar is None:
+ return {}
+ lastest_image = self.latest_image.copy()
+
+ # Set up current time variables
+ start = time.time()
+ current_time = self.vehicle_interface.time()
+
+ if downsample:
+ lidar_down = downsample_points(self.latest_lidar, voxel_size=0.1)
+ else:
+ lidar_down = self.latest_lidar.copy()
+
+ if self.start_time is None:
+ self.start_time = current_time
+ time_elapsed = current_time - self.start_time
+
+ # Ensure data/ exists and build timestamp
+ if self.save_data:
+ self.save_sensor_data(vehicle=vehicle, latest_image=latest_image)
+
+ 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 = lastest_image.copy()
+ undistorted_img = lastest_image.copy()
+ orig_H, orig_W = lastest_image.shape[:2]
+ self.current_K = self.K
+ results_normal = self.detector(img_normal, conf=0.35, classes=[0])
+ combined_boxes = []
+ if not self.enable_tracking:
+ self.cone_counter = 0
+ if self.orientation:
+ img_left = cv2.rotate(undistorted_img.copy(), cv2.ROTATE_90_COUNTERCLOCKWISE)
+ img_right = cv2.rotate(undistorted_img.copy(), cv2.ROTATE_90_CLOCKWISE)
+ results_left = self.detector(img_left, conf=0.1, classes=[0])
+ results_right = self.detector(img_right, conf=0.1, classes=[0])
+ 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 []
+ for box in boxes_left:
+ cx, cy, w, h = box
+ new_cx = cy
+ new_cy = orig_W - 1 - cx
+ combined_boxes.append((new_cx, new_cy, h, w, AgentActivityEnum.RIGHT))
+ for box in boxes_right:
+ cx, cy, w, h = box
+ new_cx = orig_H - 1 - cy
+ new_cy = cx
+ combined_boxes.append((new_cx, new_cy, h, w, AgentActivityEnum.LEFT))
+
+ 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))
+
+ # Visualize the received images in 2D with their corresponding labels
+ # It draws rectangles and labels on the images:
+ if getattr(self, 'visualize_2d', False):
+ for (cx, cy, w, h, activity) in combined_boxes:
+ left = int(cx - w / 2)
+ right = int(cx + w / 2)
+ top = int(cy - h / 2)
+ bottom = int(cy + h / 2)
+ if activity == AgentActivityEnum.STANDING:
+ color = (255, 0, 0)
+ label = "STANDING"
+ elif activity == AgentActivityEnum.RIGHT:
+ color = (0, 255, 0)
+ label = "RIGHT"
+ elif activity == AgentActivityEnum.LEFT:
+ color = (0, 0, 255)
+ label = "LEFT"
+ else:
+ color = (255, 255, 255)
+ label = "UNKNOWN"
+ cv2.rectangle(undistorted_img, (left, top), (right, bottom), color, 2)
+ cv2.putText(undistorted_img, label, (left, max(top - 5, 20)),
+ cv2.FONT_HERSHEY_SIMPLEX, 0.6, color, 2)
+ cv2.imshow("Detection - Cone 2D", undistorted_img)
+
+ 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
+
+ end = time.time()
+ # print('-------processing time1---', end -start)
+
+ agents = {}
+
+ for i, box_info in enumerate(combined_boxes):
+ cx, cy, w, h, activity = box_info
+ left = int(cx - w / 1.6)
+ right = int(cx + w / 1.6)
+ top = int(cy - h / 2)
+ bottom = int(cy + h / 2)
+ mask = (projected_pts[:, 0] >= left) & (projected_pts[:, 0] <= right) & \
+ (projected_pts[:, 1] >= top) & (projected_pts[:, 1] <= bottom)
+ roi_pts = projected_pts[mask]
+ if roi_pts.shape[0] < 5:
+ continue
+
+ points_3d = roi_pts[:, 2:5]
+ points_3d = filter_points_within_threshold(points_3d, 40)
+ 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 self.use_cyl_roi:
+ global_filtered = filter_points_within_threshold(lidar_down, 30)
+ roi_cyl = cylindrical_roi(global_filtered, np.mean(points_3d, axis=0), 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)
+ else:
+ refined_cluster = points_3d.copy()
+ # end1 = time.time()
+ if refined_cluster.shape[0] < 4:
+ continue
+
+ pcd = o3d.geometry.PointCloud()
+ pcd.points = o3d.utility.Vector3dVector(refined_cluster)
+ obb = pcd.get_oriented_bounding_box()
+ 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
+ yaw, pitch, roll = R.from_matrix(R_vehicle).as_euler('zyx', degrees=False)
+ refined_center = refined_center_vehicle
+
+ 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
+ )
+ T_vehicle_to_start = pose_to_matrix(vehicle_start_pose)
+ xp, yp, zp = (T_vehicle_to_start @ np.append(refined_center, 1))[:3]
+ out_frame = ObjectFrameEnum.START
+ else:
+ xp, yp, zp = refined_center
+ out_frame = ObjectFrameEnum.CURRENT
+
+ new_pose = ObjectPose(
+ t=current_time,
+ x=xp, y=yp, z=zp,
+ yaw=yaw, pitch=pitch, roll=roll,
+ frame=out_frame
+ )
+
+ # --- Optional tracking ---
+ if self.enable_tracking:
+ existing_id = match_existing_cone(
+ np.array([new_pose.x, new_pose.y, new_pose.z]),
+ dims,
+ self.tracked_agents,
+ distance_threshold=2.0
+ )
+ if existing_id is not None:
+ old_state = self.tracked_agents[existing_id]
+ if vehicle.v < 100:
+ alpha = 0.1
+ avg_x = alpha * new_pose.x + (1 - alpha) * old_state.pose.x
+ avg_y = alpha * new_pose.y + (1 - alpha) * old_state.pose.y
+ avg_z = alpha * new_pose.z + (1 - alpha) * old_state.pose.z
+ avg_yaw = alpha * new_pose.yaw + (1 - alpha) * old_state.pose.yaw
+ avg_pitch = alpha * new_pose.pitch + (1 - alpha) * old_state.pose.pitch
+ avg_roll = alpha * new_pose.roll + (1 - alpha) * old_state.pose.roll
+
+ updated_pose = ObjectPose(
+ t=new_pose.t,
+ x=avg_x,
+ y=avg_y,
+ z=avg_z,
+ yaw=avg_yaw,
+ pitch=avg_pitch,
+ roll=avg_roll,
+ frame=new_pose.frame
+ )
+ updated_agent = AgentState(
+ pose=updated_pose,
+ dimensions=dims,
+ outline=None,
+ type=AgentEnum.CONE,
+ activity=activity,
+ velocity=(0, 0, 0),
+ yaw_rate=0
+ )
+ else:
+ updated_agent = old_state
+ agents[existing_id] = updated_agent
+ self.tracked_agents[existing_id] = updated_agent
+ else:
+ agent_id = f"Cone{self.cone_counter}"
+ self.cone_counter += 1
+ new_agent = AgentState(
+ pose=new_pose,
+ dimensions=dims,
+ outline=None,
+ type=AgentEnum.CONE,
+ activity=activity,
+ velocity=(0, 0, 0),
+ yaw_rate=0
+ )
+ agents[agent_id] = new_agent
+ self.tracked_agents[agent_id] = new_agent
+ else:
+ agent_id = f"Cone{self.cone_counter}"
+ self.cone_counter += 1
+ new_agent = AgentState(
+ pose=new_pose,
+ dimensions=dims,
+ outline=None,
+ type=AgentEnum.CONE,
+ activity=activity,
+ velocity=(0, 0, 0),
+ yaw_rate=0
+ )
+ agents[agent_id] = new_agent
+
+ self.current_agents = agents
+
+ # If tracking not enabled, return only current frame detections
+ if not self.enable_tracking:
+ 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}"
+ )
+ end = time.time()
+ # print('-------processing time', end -start)
+ return self.current_agents
+
+ stale_ids = [agent_id for agent_id, agent in self.tracked_agents.items()
+ if current_time - agent.pose.t > 20.0]
+ for agent_id in stale_ids:
+ rospy.loginfo(f"Removing stale agent: {agent_id}\n")
+ del self.tracked_agents[agent_id]
+ if self.enable_tracking:
+ for agent_id, agent in self.tracked_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}"
+ )
+ end = time.time()
+ # print('-------processing time', end -start)
+ return self.tracked_agents
+
+ def save_sensor_data(self, vehicle: VehicleState, latest_image) -> None:
+ os.makedirs("data", exist_ok=True)
+ tstamp = int(self.vehicle_interface.time() * 1000)
+ # 1) Dump raw image
+ cv2.imwrite(f"data/{tstamp}_image.png", lastest_image)
+ # 2) Dump raw LiDAR
+ np.savez(f"data/{tstamp}_lidar.npz", lidar=self.latest_lidar)
+ # 3) Write BEFORE_TRANSFORM
+ with open(f"data/{tstamp}_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 vehicle_start_pose in either START or CURRENT
+ 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/{tstamp}_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 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):
+ 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/pedestrian_detection.py b/GEMstack/onboard/perception/pedestrian_detection.py
new file mode 100644
index 000000000..be4001e76
--- /dev/null
+++ b/GEMstack/onboard/perception/pedestrian_detection.py
@@ -0,0 +1,820 @@
+from ...state import AllState, VehicleState, ObjectPose, ObjectFrameEnum, AgentState, AgentEnum, AgentActivityEnum
+from ..interface.gem import GEMInterface
+from ..component import Component
+from ultralytics import YOLO
+import cv2
+from typing import Dict
+import open3d as o3d
+import numpy as np
+from sklearn.cluster import DBSCAN
+from scipy.spatial.transform import Rotation as R
+import rospy
+from sensor_msgs.msg import PointCloud2, Image
+import sensor_msgs.point_cloud2 as pc2
+import struct, ctypes
+from message_filters import Subscriber, ApproximateTimeSynchronizer
+from cv_bridge import CvBridge
+import time
+
+'''
+The following function is contributed by Aavi Deora
+Essentially this method is simliar to teamB's method, i.e. transform point cloud from lidar to image frame
+Though we find this calculation is heavy, this method have potential usage in other parts, e.g. replacing DBSCAN
+'''
+
+# def get_average_cam_point_from_lidar(bbox, point_cloud):
+# """
+# Given a bounding box (x, y, w, h) in image coordinates and a lidar point cloud (in the lidar frame),
+# this function:
+# 1. Converts the point cloud to homogeneous coordinates.
+# 2. Transforms the points into the camera frame using LIDAR_TO_CAMERA_TRANSFORM.
+# 3. Projects the points into the image using the camera intrinsics.
+# 4. Selects points that fall inside the bounding box.
+# 5. Returns the average 3D point (in the camera frame) of those points.
+#
+# Returns:
+# avg_point: A NumPy array [x_cam, y_cam, z_cam] in the camera frame,
+# or None if no points are found inside the bbox.
+# """
+# x, y, w, h = bbox
+# if point_cloud is None or point_cloud.shape[0] == 0:
+# return None
+#
+# # Convert the point cloud (assumed shape (N,3)) to homogeneous coordinates (N,4)
+# ones = np.ones((point_cloud.shape[0], 1))
+# points_homog = np.hstack((point_cloud, ones)) # shape (N,4)
+#
+# # Transform points from lidar frame to camera frame
+# cam_points_homog = (LIDAR_TO_CAMERA_TRANSFORM @ points_homog.T).T # shape (N,4)
+# cam_points = cam_points_homog[:, :3] # (x_cam, y_cam, z_cam)
+#
+# # Only consider points in front of the camera (z_cam > 0)
+# valid_mask = cam_points[:, 2] > 0
+# cam_points = cam_points[valid_mask]
+# if cam_points.shape[0] == 0:
+# return None
+#
+# # Project points into the image using the pinhole camera model:
+# # u = fx * (x_cam / z_cam) + cx, v = fy * (y_cam / z_cam) + cy
+# u = CAMERA_INTRINSICS['fx'] * (cam_points[:, 0] / cam_points[:, 2]) + CAMERA_INTRINSICS['cx']
+# v = CAMERA_INTRINSICS['fy'] * (cam_points[:, 1] / cam_points[:, 2]) + CAMERA_INTRINSICS['cy']
+#
+# # Create a mask for points that fall within the bounding box.
+# in_bbox_mask = (u >= x) & (u <= x + w) & (v >= y) & (v <= y + h)
+# if np.sum(in_bbox_mask) == 0:
+# return None
+#
+# selected_points = cam_points[in_bbox_mask]
+# return selected_points
+
+
+'''
+The following function is contributed by Shuning Liu.
+Since the height and velocity detection is not entirely stable, we are not using this matching logic currently.
+But we may also test a more robust version of this in future on board test.
+'''
+
+# def match_existing_pedestrian(
+# new_center: np.ndarray,
+# new_dims: tuple,
+# existing_agents: Dict[str, AgentState],
+# prev_velocities: Dict[str, np.ndarray],
+# distance_threshold: float = 1.0,
+# size_threshold: float = 0.5,
+# height_threshold: float = 0.3,
+# velocity_threshold: float = 2.0
+# ) -> str:
+# """
+# Match a newly detected pedestrian with an existing one using:
+# - Euclidean distance
+# - Bounding box similarity
+# - Height consistency
+# - Velocity consistency
+#
+# Returns the best-matching agent_id or None if no good match is found.
+# """
+# best_agent_id = None
+# best_score = 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])
+# old_dims = agent_state.dimensions
+#
+# # 1. Euclidean Distance Check
+# dist = np.linalg.norm(new_center - old_center)
+# if dist > distance_threshold:
+# continue # Skip if too far away
+#
+# # 2. Bounding Box Size Similarity (with Zero-Division Handling)
+# size_norm = np.linalg.norm(np.array(old_dims))
+# if size_norm > 0:
+# size_change = np.linalg.norm(np.array(new_dims) - np.array(old_dims)) / size_norm
+# else:
+# size_change = float('inf') # Prevent invalid matching
+#
+# if size_change > size_threshold:
+# continue # Skip if bounding box changes too much
+#
+# # 3. Height Consistency Check
+# height_change = abs(new_dims[2] - old_dims[2]) / old_dims[2] if old_dims[2] > 0 else 0
+# if height_change > height_threshold:
+# continue # Skip if height changes drastically
+#
+# # 4. Velocity Consistency Check
+# if agent_id in prev_velocities:
+# prev_velocity = prev_velocities[agent_id]
+# estimated_velocity = (new_center - old_center)
+# velocity_change = np.linalg.norm(estimated_velocity - prev_velocity)
+#
+# if velocity_change > velocity_threshold:
+# continue # Skip if unrealistic velocity jump
+#
+# # Score: Lower score = better match (distance is primary factor)
+# score = dist
+# if score < best_score:
+# best_score = score
+# best_agent_id = agent_id
+#
+# return best_agent_id
+
+'''
+The following function is contributed by Justin Li. An alternative to basic distance-based matching
+We plan to test this new tracking logic in the next on board test
+'''
+
+class BoundingBox:
+ """
+ center: center of bounding box in x, y, z coordinates
+ dimensions: dimensions of bounding box in x, y, z format
+ orientation: 3x3 rotation matrix
+ """
+
+ def __init__(
+ self,
+ center: tuple[float, float, float],
+ dimensions: tuple[float, float, float],
+ orientation: list[list[float]],
+ ):
+ self.center = np.array(center)
+ self.dimensions = np.array(dimensions)
+ self.orientation = np.array(orientation)
+
+def obb_collision(box1: BoundingBox, box2: BoundingBox):
+ """
+ Checks if two oriented bounding boxes (OBBs) collide using the Separating Axis Theorem (SAT).
+
+ :param box1: Box with 'center' (x, y, z), 'dimensions' (dx, dy, dz), and 'orientation' (3x3 rotation matrix)
+ :param box2: Box with 'center' (x, y, z), 'dimensions' (dx, dy, dz), and 'orientation' (3x3 rotation matrix)
+ :return: Boolean indicating whether the two OBBs collide
+ """
+
+ def get_axes(rotation_matrix):
+ """Extracts the axes from the rotation matrix."""
+ return [rotation_matrix[:, i] for i in range(3)]
+
+ def project_obb(obb: BoundingBox, axis):
+ """Projects the OBB onto a given axis and returns the min and max values."""
+ center_proj = np.dot(obb.center, axis)
+ extents = np.abs(np.dot(obb.orientation, np.diag(obb.dimensions / 2.0)))
+ radius = np.sum(extents * np.abs(axis))
+ return center_proj - radius, center_proj + radius
+
+ def overlap_on_axis(axis, box1, box2):
+ """Checks if the projections of two OBBs overlap on the given axis."""
+ min1, max1 = project_obb(box1, axis)
+ min2, max2 = project_obb(box2, axis)
+ return max1 >= min2 and max2 >= min1
+
+ # Get OBB axes
+ axes1 = get_axes(box1.orientation)
+ axes2 = get_axes(box2.orientation)
+
+ # Compute cross products of axes for possible separating axes
+ cross_axes = [np.cross(a1, a2) for a1 in axes1 for a2 in axes2]
+
+ # Test all axes
+ for axis in axes1 + axes2 + cross_axes:
+ if np.linalg.norm(axis) > 1e-6: # Avoid near-zero axes
+ axis = axis / np.linalg.norm(axis) # Normalize
+ if not overlap_on_axis(axis, box1, box2):
+ return False # Separating axis found, no collision
+
+ return True # No separating axis found, collision detected
+
+
+# ----- Helper Functions -----
+
+def match_existing_pedestrian(
+ new_center: np.ndarray,
+ new_dims: tuple,
+ existing_agents: Dict[str, AgentState],
+ distance_threshold: float = 1.0
+) -> str:
+ """
+ Find the closest existing pedestrian agent within a specified distance threshold.
+
+ Args:
+ new_center (np.ndarray): The 3D center (x,y,z) of the new detection.
+ new_dims (tuple): The dimensions of the new detection (currently unused).
+ existing_agents (Dict[str, AgentState]): Dictionary of currently tracked agents.
+ distance_threshold (float): Maximum allowed distance to consider a match.
+
+ Returns:
+ str: The agent_id of the best matching pedestrian if within the threshold; otherwise, None.
+ """
+ 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 velocity vector (vx, vy, vz) based on change in pose over a time interval.
+
+ Args:
+ old_pose (ObjectPose): The previous pose.
+ new_pose (ObjectPose): The current pose.
+ dt (float): Time elapsed between the poses.
+
+ Returns:
+ tuple: (vx, vy, vz) velocity in the same coordinate frame as the input poses.
+ """
+ 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):
+ """
+ Extract a region of interest (ROI) from the LiDAR point cloud defined by an axis-aligned bounding box.
+
+ Args:
+ lidar_pc (np.ndarray): The LiDAR point cloud as an (N, 3) array.
+ center (np.ndarray): Center of the ROI box.
+ half_extents (np.ndarray): Half-lengths in each dimension defining the box.
+
+ Returns:
+ np.ndarray: Subset of points within the ROI.
+ """
+ lower = center - half_extents
+ upper = center + half_extents
+ mask = np.all((lidar_pc >= lower) & (lidar_pc <= upper), axis=1)
+ return lidar_pc[mask]
+
+
+def pc2_to_numpy(pc2_msg, want_rgb=False):
+ """
+ Convert a ROS PointCloud2 message into a numpy array with basic filtering.
+
+ This function extracts the x, y, z coordinates from the point cloud and
+ filters out points with x <= 0 and z >= 2.5.
+
+ Args:
+ pc2_msg: The ROS PointCloud2 message.
+ want_rgb (bool): Flag to indicate if RGB data is desired (not used here).
+
+ Returns:
+ np.ndarray: Filtered point cloud array of shape (N, 3).
+ """
+ gen = pc2.read_points(pc2_msg, skip_nans=True)
+ pts = np.array(list(gen), dtype=np.float32)
+ pts = pts[:, :3] # Only x, y, z coordinates
+ mask = (pts[:, 0] > 0) & (pts[:, 2] < 2.5)
+ return pts[mask]
+
+
+def backproject_pixel(u, v, K):
+ """
+ Backproject a pixel coordinate (u, v) into a normalized 3D ray in the camera coordinate system.
+
+ Args:
+ u (float): The pixel's x-coordinate.
+ v (float): The pixel's y-coordinate.
+ K (np.ndarray): The 3x3 camera intrinsic matrix.
+
+ Returns:
+ np.ndarray: A unit vector representing the 3D ray direction.
+ """
+ cx, cy = K[0, 2], K[1, 2]
+ fx, fy = K[0, 0], K[1, 1]
+ x = (u - cx) / fx
+ y = (v - cy) / fy
+ ray_dir = np.array([x, y, 1.0])
+ return ray_dir / np.linalg.norm(ray_dir)
+
+
+def find_human_center_on_ray(lidar_pc, ray_origin, ray_direction,
+ t_min, t_max, t_step,
+ distance_threshold, min_points, ransac_threshold):
+ """
+ Identify the center of a human detected along a projected ray.
+
+ This function first filters the LiDAR points to only those near the ray. Then it
+ sweeps along the ray (from t_min to t_max in steps of t_step) to find a candidate
+ location where enough points (>= min_points) lie within the distance_threshold.
+
+ Args:
+ lidar_pc (np.ndarray): LiDAR point cloud in 3D.
+ ray_origin (np.ndarray): Origin of the ray in LiDAR coordinates.
+ ray_direction (np.ndarray): Normalized direction of the ray.
+ t_min (float): Minimum distance along the ray to start searching.
+ t_max (float): Maximum distance along the ray.
+ t_step (float): Increment along the ray.
+ distance_threshold (float): Maximum distance from the ray for a point to be considered.
+ min_points (int): Minimum number of points needed to validate a candidate.
+ ransac_threshold (float): (Unused in current implementation) threshold for RANSAC.
+
+ Returns:
+ tuple: (refined_candidate, None, None) if a valid candidate is found; otherwise, (None, None, None).
+ """
+ # Compute projection distances and the corresponding points on the ray.
+ vecs = lidar_pc - ray_origin
+ proj_lengths = np.dot(vecs, ray_direction)
+ proj_points = ray_origin + np.outer(proj_lengths, ray_direction)
+ dists_to_ray = np.linalg.norm(lidar_pc - proj_points, axis=1)
+ near_ray_mask = dists_to_ray < distance_threshold
+ filtered_pc = lidar_pc[near_ray_mask]
+
+ if filtered_pc.shape[0] < min_points:
+ return None, None, None
+
+ # Sweep along the ray to locate a cluster of points.
+ t_values = np.arange(t_min, t_max, t_step)
+ for t in t_values:
+ candidate = ray_origin + t * ray_direction
+ dists = np.linalg.norm(filtered_pc - candidate, axis=1)
+ nearby_points = filtered_pc[dists < distance_threshold]
+ if nearby_points.shape[0] >= min_points:
+ refined_candidate = np.mean(nearby_points, axis=0)
+ return refined_candidate, None, None
+ return None, None, None
+
+
+def extract_roi(pc, center, roi_radius):
+ """
+ Extract points from a point cloud that lie within a specified radius of a center point.
+
+ Args:
+ pc (np.ndarray): The point cloud array.
+ center (np.ndarray): The 3D center point.
+ roi_radius (float): The radius of the region of interest.
+
+ Returns:
+ np.ndarray: Points from pc that are within roi_radius of center.
+ """
+ distances = np.linalg.norm(pc - center, axis=1)
+ return pc[distances < roi_radius]
+
+
+def refine_cluster(roi_points, center, eps=0.2, min_samples=10):
+ """
+ Refine a point cluster by applying DBSCAN and selecting the cluster closest to a given center.
+
+ Args:
+ roi_points (np.ndarray): Points within a region of interest.
+ center (np.ndarray): The expected center of the cluster.
+ eps (float): The maximum distance between two samples for one to be considered in the neighborhood of the other.
+ min_samples (int): The number of samples required in a neighborhood for a point to be considered as a core point.
+
+ Returns:
+ np.ndarray: The refined cluster points. If no clusters are found, returns the original 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 ground points from a cluster by excluding points that lie close to the minimum z value.
+
+ Args:
+ cluster (np.ndarray): The input point cluster.
+ z_range (float): The threshold range above the minimum z-value to consider as ground.
+
+ Returns:
+ np.ndarray: The cluster with ground points removed.
+ """
+ if cluster is None or cluster.shape[0] == 0:
+ return cluster
+ min_z = np.min(cluster[:, 2])
+ filtered = cluster[cluster[:, 2] > (min_z + z_range)]
+ return filtered
+
+
+def get_bounding_box_center_and_dimensions(points):
+ """
+ Calculate the axis-aligned bounding box's center and dimensions for a set of 3D points.
+
+ Args:
+ points (np.ndarray): The input points.
+
+ Returns:
+ tuple: (center, dimensions) where center is the midpoint of the bounding box and dimensions is (max - min).
+ Returns (None, None) if the input is empty.
+ """
+ if points.shape[0] == 0:
+ return None, None
+ min_vals = np.min(points, axis=0)
+ max_vals = np.max(points, axis=0)
+ center = (min_vals + max_vals) / 2
+ dimensions = max_vals - min_vals
+ return center, dimensions
+
+
+def create_ray_line_set(start, end):
+ """
+ Create an Open3D LineSet object representing a ray between two 3D points.
+
+ The line is colored yellow.
+
+ Args:
+ start (np.ndarray): The start point of the ray.
+ end (np.ndarray): The end point of the ray.
+
+ Returns:
+ o3d.geometry.LineSet: The LineSet object representing the ray.
+ """
+ points = [start, end]
+ lines = [[0, 1]]
+ line_set = o3d.geometry.LineSet()
+ line_set.points = o3d.utility.Vector3dVector(points)
+ line_set.lines = o3d.utility.Vector2iVector(lines)
+ line_set.colors = o3d.utility.Vector3dVector([[1, 1, 0]])
+ return line_set
+
+
+def visualize_geometries(geometries, window_name="Open3D", width=800, height=600, point_size=5.0):
+ """
+ Visualize a list of Open3D geometry objects in a dedicated window.
+
+ Args:
+ geometries (list): A list of Open3D geometry objects.
+ window_name (str): Title of the visualization window.
+ width (int): Width of the window.
+ height (int): Height of the window.
+ point_size (float): Size of the rendered points.
+ """
+ vis = o3d.visualization.Visualizer()
+ vis.create_window(window_name=window_name, width=width, height=height)
+ for geom in geometries:
+ vis.add_geometry(geom)
+ opt = vis.get_render_option()
+ opt.point_size = point_size
+ vis.run()
+ vis.destroy_window()
+
+
+# ----- Pedestrian Detector 2D (with 3D Fusion and Synchronized Callbacks) -----
+
+class PedestrianDetector2D(Component):
+ """
+ Detects pedestrians by fusing 2D YOLO detections with LiDAR point cloud data to estimate 3D poses.
+
+ This implementation uses message_filters to synchronize incoming RGB images and LiDAR data.
+ The synchronized callback caches the latest sensor data for processing in the update() method.
+ """
+
+ def __init__(self, vehicle_interface: GEMInterface):
+ self.vehicle_interface = vehicle_interface
+ self.current_agents = {}
+ self.tracked_agents = {}
+ self.pedestrian_counter = 0
+ # Variables to store the most recent synchronized sensor data:
+ self.latest_image = None
+ self.latest_lidar = None
+ self.bridge = CvBridge()
+
+ def rate(self) -> float:
+ # Process data at 4 Hz.
+ return 4.0
+
+ def state_inputs(self) -> list:
+ # Expects vehicle state information as input.
+ return ['vehicle']
+
+ def state_outputs(self) -> list:
+ # Outputs detected pedestrian agents.
+ return ['agents']
+
+ def initialize(self):
+ """
+ Initialize sensor subscriptions and the YOLO detector.
+
+ Uses message_filters to synchronize the image and LiDAR data streams.
+ Also sets up the camera intrinsic matrix and LiDAR-to-camera (and vehicle) transformations.
+ """
+ self.rgb_sub = Subscriber('/oak/rgb/image_raw', 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)
+ # Initialize YOLO detector with the pretrained model and set to CUDA.
+ self.detector = YOLO('../../knowledge/detection/yolov8s.pt')
+ self.detector.to('cuda')
+ # Camera intrinsic matrix.
+ self.K = np.array([[684.83331299, 0., 573.37109375],
+ [0., 684.60968018, 363.70092773],
+ [0., 0., 1.]])
+ # LiDAR-to-vehicle transformation matrix.
+ 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.]])
+ # LiDAR-to-camera transformation matrix.
+ self.T_l2c = np.array([
+ [0.001090, -0.999489, -0.031941, 0.149698],
+ [-0.007664, 0.031932, -0.999461, -0.397813],
+ [0.999970, 0.001334, -0.007625, -0.691405],
+ [0.000000, 0.000000, 0.000000, 1.000000]
+ ])
+ # Inverse transformation: camera-to-LiDAR.
+ self.T_c2l = np.linalg.inv(self.T_l2c)
+ self.R_c2l = self.T_c2l[:3, :3]
+ # Camera origin expressed in LiDAR coordinates.
+ self.camera_origin_in_lidar = self.T_c2l[:3, 3]
+
+ def synchronized_callback(self, image_msg, lidar_msg):
+ """
+ Callback function that is invoked when an image and a LiDAR message are received within the allowed time difference.
+
+ This function converts the ROS messages into usable formats:
+ - The image is converted to an OpenCV BGR image.
+ - The LiDAR message is converted to a numpy array.
+ """
+ try:
+ self.latest_image = self.bridge.imgmsg_to_cv2(image_msg, "bgr8")
+ except Exception as e:
+ rospy.logerr("Failed to convert image: {}".format(e))
+ self.latest_image = None
+ self.latest_lidar = pc2_to_numpy(lidar_msg, want_rgb=False)
+
+ def update(self, vehicle: VehicleState) -> Dict[str, AgentState]:
+ """
+ Process the latest synchronized sensor data to detect pedestrians and estimate their 3D poses.
+
+ This method performs the following:
+ 1. Runs YOLO on the latest image to obtain 2D pedestrian detections.
+ 2. Backprojects the 2D detections into 3D rays in the LiDAR frame.
+ 3. Uses LiDAR data along the ray to estimate a 3D position (and size) for the pedestrian.
+ 4. Matches detections to existing tracked agents or creates new ones.
+
+ Args:
+ vehicle (VehicleState): The current vehicle state.
+
+ Returns:
+ Dict[str, AgentState]: Dictionary mapping agent IDs to their updated states.
+ """
+ # 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()
+ # Run YOLO inference on the current image (detecting only class 0, e.g., persons).
+ results = self.detector(self.latest_image, conf=0.4, classes=[0])
+ boxes = np.array(results[0].boxes.xywh.cpu()) # Format: [center_x, center_y, width, height]
+
+ agents = {}
+ lidar_pc = self.latest_lidar.copy()
+
+ for i, box in enumerate(boxes):
+ cx, cy, w, h = box
+ # Backproject the 2D pixel center into a 3D ray in the LiDAR coordinate frame.
+ ray_dir_cam = backproject_pixel(cx, cy, self.K)
+ ray_dir_lidar = self.R_c2l @ ray_dir_cam
+ ray_dir_lidar /= np.linalg.norm(ray_dir_lidar)
+
+ # Attempt to locate the pedestrian's center along the ray using LiDAR data.
+ intersection, _, _ = find_human_center_on_ray(
+ lidar_pc, self.camera_origin_in_lidar, ray_dir_lidar,
+ t_min=0.4, t_max=25.0, t_step=0.1,
+ distance_threshold=0.5, min_points=5, ransac_threshold=0.05
+ )
+ if intersection is None:
+ # If no valid intersection is found, update the positions of already tracked agents
+ # based on the vehicle's forward velocity and time elapsed.
+ for agent in self.tracked_agents.values():
+ dt = current_time - agent.pose.t
+ agent.pose.x -= vehicle.v * dt # Adjust x-coordinate assuming vehicle moves forward along x.
+ agent.pose.t = current_time
+ continue
+
+ # Estimate the pedestrian's physical dimensions using the detection box size and distance.
+ d = np.linalg.norm(intersection - self.camera_origin_in_lidar)
+ physical_width = (w * d) / self.K[0, 0]
+ physical_height = (h * d) / self.K[1, 1]
+ # Since the depth (x-direction) measurement is less reliable, use an empirical value.
+ half_extents = np.array([0.4, 1.1 * physical_width / 2, 1.1 * physical_height / 2])
+
+ # Extract LiDAR points within the ROI box around the estimated intersection.
+ roi_points = extract_roi_box(lidar_pc, intersection, half_extents)
+ if roi_points.shape[0] < 10:
+ refined_cluster = roi_points
+ else:
+ refined_cluster = refine_cluster(roi_points, intersection, eps=0.15, min_samples=10)
+
+ # Remove ground points from the refined cluster.
+ refined_cluster = remove_ground_by_min_range(refined_cluster, z_range=0.03)
+ if refined_cluster is None or refined_cluster.shape[0] == 0:
+ # Fallback to the initial intersection if no valid cluster remains.
+ refined_center = intersection
+ dims = (0, 0, 0)
+ yaw, pitch, roll = 0, 0, 0
+ elif refined_cluster.shape[0] <= 5:
+ # Skip detections with insufficient LiDAR points.
+ continue
+ else:
+ # Create an Open3D point cloud from the refined cluster and compute its oriented bounding box.
+ pcd = o3d.geometry.PointCloud()
+ pcd.points = o3d.utility.Vector3dVector(refined_cluster)
+ obb = pcd.get_oriented_bounding_box()
+ refined_center = obb.center
+ dims = tuple(obb.extent)
+ R_lidar = obb.R.copy()
+
+ # Transform the refined center from LiDAR coordinates to the vehicle frame.
+ refined_center_lidar_hom = np.array([refined_center[0],
+ refined_center[1],
+ refined_center[2],
+ 1.0])
+ refined_center_vehicle_hom = self.T_l2v @ refined_center_lidar_hom
+ refined_center_vehicle = refined_center_vehicle_hom[:3]
+
+ # Compute the orientation (yaw, pitch, roll) in the vehicle frame.
+ R_vehicle = self.T_l2v[:3, :3] @ R_lidar
+ euler_angles_vehicle = R.from_matrix(R_vehicle).as_euler('zyx', degrees=False)
+ yaw, pitch, roll = euler_angles_vehicle
+ refined_center = refined_center_vehicle # Use vehicle frame coordinates for output
+
+ '''
+ Note that this part can be used for converting the speed relative to vehicle -> speed relative to START frame
+ However, the VehicleState may read in Global coordinate (i.e. long and lat) instead of relative to START frame
+ In order to avoid this issue, we found it is actually easier to implement this in the planning code.
+ Planning function has access to Allstate instead of just Vehicle state,
+ therefore it is easier to specify which coordinate system to use
+ '''
+ '''
+ i.e. Simliar function is implemented in GEMstack/onboard/planning/pedestrian_yield_logic.py L569-573
+ # 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
+ '''
+ # curr_x = vehicle.pose.x
+ # curr_y = vehicle.pose.y
+ # curr_yaw = vehicle.pose.yaw
+ # curr_pitch = vehicle.pose.pitch
+ # curr_roll = vehicle.pose.roll
+ # refined_center[0] += curr_x
+ # refined_center[1] += curr_y
+ # euler_angles_vehicle[0] += curr_yaw
+ # euler_angles_vehicle[1] += curr_pitch
+ # euler_angles_vehicle[2] += curr_roll
+
+ # Create a new pose for the detected pedestrian in the vehicle frame.
+ new_pose = ObjectPose(
+ t=current_time,
+ x=refined_center[0],
+ y=refined_center[1],
+ z=refined_center[2],
+ yaw=yaw,
+ pitch=pitch,
+ roll=roll,
+ frame=ObjectFrameEnum.CURRENT
+ )
+
+ # Attempt to match the new detection with an existing tracked pedestrian.
+ existing_id = match_existing_pedestrian(
+ 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:
+ # Update the state of the matched pedestrian using the computed velocity.
+ old_agent_state = self.tracked_agents[existing_id]
+ dt = new_pose.t - old_agent_state.pose.t
+ '''
+ We found that the velocity calculated here is not entirely stable.
+ We are implementing a more stable method, e.g. kalman filter based one
+ '''
+ vx, vy, vz = compute_velocity(old_agent_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:
+ # If no match is found, create a new pedestrian agent.
+ agent_id = f"pedestrian{self.pedestrian_counter}"
+ self.pedestrian_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.current_agents = agents
+
+ 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}")
+ del self.tracked_agents[agent_id]
+ # Log the details of each detected agent.
+ for agent_id, agent in agents.items():
+ rospy.loginfo(f"Agent ID: {agent_id}, Pose: {agent.pose}, Velocity: {agent.velocity}")
+
+ return agents
+
+
+# ----- Fake Pedestrian Detector 2D (for Testing Purposes) -----
+
+class FakePedestrianDetector2D(Component):
+ """
+ A dummy pedestrian detector that simulates detections during pre-defined time intervals.
+
+ This component is useful for testing the overall system without relying on real sensor data.
+ """
+
+ 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['pedestrian0'] = box_to_fake_agent((0, 0, 0, 0))
+ rospy.loginfo("Detected a pedestrian (simulated)")
+ return res
+
+
+def box_to_fake_agent(box):
+ """
+ Create a fake AgentState from a bounding box represented as (x, y, width, height).
+
+ The pose is computed using the center of the box, and the dimensions are treated as 2D approximations.
+
+ Args:
+ box (tuple): A tuple (x, y, w, h) representing the bounding box.
+
+ Returns:
+ AgentState: The simulated pedestrian agent.
+ """
+ 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__':
+ # This module is intended to be used within the vehicle interface context.
+ # For standalone testing, instantiate a fake vehicle state and call update().
+ pass
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/state_estimation.py b/GEMstack/onboard/perception/state_estimation.py
index 4aef25659..4d19d4fa4 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/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/longitudinal_planning.py b/GEMstack/onboard/planning/longitudinal_planning.py
new file mode 100644
index 000000000..f2657c67d
--- /dev/null
+++ b/GEMstack/onboard/planning/longitudinal_planning.py
@@ -0,0 +1,739 @@
+from typing import List, Tuple, Union
+from ..component import Component
+from ...state import AllState, VehicleState, EntityRelation, EntityRelationEnum, Path, Trajectory, Route, ObjectFrameEnum, AgentState
+from ...utils import serialization, settings
+from ...mathutils.transforms import vector_madd
+from ...mathutils.quadratic_equation import quad_root
+
+import numpy as np
+import math
+
+
+################################################################################
+########## Longitudinal Planning ###############################################
+################################################################################
+
+def longitudinal_plan(path : Path, acceleration : float, deceleration : float, max_speed : float, current_speed : float,
+ method : str) -> Trajectory:
+ """Generates a longitudinal trajectory for a path with a
+ trapezoidal velocity profile.
+
+ 1. accelerates from current speed toward max speed
+ 2. travel along max speed
+ 3. if at any point you can't brake before hitting the end of the path,
+ decelerate with accel = -deceleration until velocity goes to 0.
+ """
+
+ if method == "milestone":
+ return longitudinal_plan_milestone(path, acceleration, deceleration, max_speed, current_speed)
+ elif method == "dt":
+ return longitudinal_plan_dt(path, acceleration, deceleration, max_speed, current_speed)
+ elif method == "dx":
+ return longitudinal_plan_dx(path, acceleration, deceleration, max_speed, current_speed)
+ else:
+ raise NotImplementedError("Invalid method, only milestone, dt, adn dx are implemented.")
+
+########################
+##### Simon's Code #####
+########################
+def longitudinal_plan_milestone(path : Path, acceleration : float, deceleration : float, max_speed : float, current_speed : float) -> Trajectory:
+ """Generates a longitudinal trajectory for a path with a
+ trapezoidal velocity profile.
+
+ 1. accelerates from current speed toward max speed
+ 2. travel along max speed
+ 3. if at any point you can't brake before hitting the end of the path,
+ decelerate with accel = -deceleration until velocity goes to 0.
+ """
+ # Extrapolation factor for the points
+ # @TODO this should be moved to a parameter/allow dx to handle the case
+ # where we need more points
+ factor = 5.0
+ new_points = []
+ for idx, point in enumerate(path.points[:-1]):
+ next_point = path.points[idx+1]
+ if point[0] == next_point[0]:
+ break
+ xarange = np.arange(point[0], next_point[0], (next_point[0] - point[0])/factor)
+ if point[1] == next_point[1]:
+ yarange = [point[1]]*len(xarange)
+ else:
+ yarange = np.arange(point[1], next_point[1], (next_point[1] - point[1])/factor)
+ for x, y in zip(xarange, yarange):
+ new_points.append((x, y))
+ new_points.append(path.points[-1])
+
+ path = Path(path.frame, new_points)
+
+ path_normalized = path.arc_length_parameterize()
+ points = [p for p in path_normalized.points]
+ times = [t for t in path_normalized.times]
+ #=============================================
+
+ print("-----LONGITUDINAL PLAN-----")
+ #print("path length: ", path.length())
+ length = path.length()
+
+ # If the path is too short, just return the path for preventing sudden halt of simulation
+ if length < 0.05:
+ return Trajectory(path.frame, points, times)
+
+ # Starting point
+ x0 = points[0][0]
+ cur_point = points[0]
+ cur_time = times[0]
+ cur_index = 0
+
+ new_points = []
+ new_times = []
+ velocities = [] # for graphing and debugging purposes
+
+ while current_speed > 0 or cur_index == 0:
+ # we want to iterate through all the points and add them
+ # to the new points. However, we also want to add "switch points"
+ # where we reach top speed, begin decelerating, and stop
+ new_points.append(cur_point)
+ new_times.append(cur_time)
+ velocities.append(current_speed)
+
+ # Information we will need:
+ # Calculate how much time it would take to stop
+ # Calculate how much distance it would take to stop
+ min_delta_t_stop = current_speed/deceleration
+ min_delta_x_stop = current_speed*min_delta_t_stop - 0.5*deceleration*min_delta_t_stop**2
+ # print(min_delta_x_stop)
+ assert min_delta_x_stop >= 0
+
+ # If we cannot stop before or stop exactly at the final position requested
+ if cur_point[0] + min_delta_x_stop >= points[-1][0]:
+ # put on the breaks
+
+ # Calculate the next point in a special manner because of too-little time to stop
+ if cur_index == len(points)-1:
+ # the next point in this instance would be when we stop
+ next_point = (cur_point[0] + min_delta_x_stop, 0)
+ else:
+ next_point = points[cur_index+1]
+
+ # keep breaking until the next milestone in path
+ if next_point[0] <= points[-1][0]:
+ # print("continuing to next point")
+ delta_t_to_next_x = compute_time_to_x(cur_point[0], next_point[0], current_speed, -deceleration)
+ cur_time += delta_t_to_next_x
+ cur_point = next_point
+ current_speed -= deceleration*delta_t_to_next_x
+ cur_index += 1
+ else:
+ # continue to the point in which we would stop (current_velocity = 0)
+ # update to the next point
+ delta_t_to_next_x = compute_time_to_x(cur_point[0], next_point[0], current_speed, -deceleration)
+ cur_point = next_point
+ cur_time += delta_t_to_next_x
+ # current_speed would not be exactly zero error would be less than 1e-4 but perfer to just set to zero
+ #current_speed -= delta_t_to_next_x*deceleration
+ current_speed = 0
+ assert current_speed == 0
+
+ # This is the case where we are accelerating to max speed
+ # because the first if-statement covers for when we decelerating,
+ # the only time current_speed < max_speed is when we are accelerating
+ elif current_speed < max_speed:
+ # next point
+ next_point = points[cur_index+1]
+ # accelerate to max speed
+
+ # calculate the time it would take to reach max speed
+ delta_t_to_max_speed = (max_speed - current_speed)/acceleration
+ # calculate the distance it would take to reach max speed
+ delta_x_to_max_speed = current_speed*delta_t_to_max_speed + 0.5*acceleration*delta_t_to_max_speed**2
+
+ delta_t_to_stop_from_max_speed = max_speed/deceleration
+ delta_x_to_stop_from_max_speed = max_speed*delta_t_to_stop_from_max_speed - 0.5*deceleration*delta_t_to_stop_from_max_speed**2
+
+ delta_t_to_next_point = compute_time_to_x(cur_point[0], next_point[0], current_speed, acceleration)
+ velocity_at_next_point = current_speed + delta_t_to_next_point*acceleration
+ time_to_stop_from_next_point = velocity_at_next_point/deceleration
+ delta_x_to_stop_from_next_point = velocity_at_next_point*time_to_stop_from_next_point - 0.5*deceleration*time_to_stop_from_next_point**2
+ # if we would reach max speed after the next point,
+ # just move to the next point and update the current speed and time
+ if next_point[0] + delta_x_to_stop_from_next_point < points[-1][0] and \
+ cur_point[0] + delta_x_to_max_speed >= next_point[0]:
+ # go to next point
+ # accelerate to max speed
+ delta_t_to_next_x = compute_time_to_x(cur_point[0], next_point[0], current_speed, acceleration)
+ cur_time += delta_t_to_next_x
+ cur_point = [next_point[0], 0]
+ current_speed += delta_t_to_next_x*acceleration
+ cur_index += 1
+
+ # This is the case where we would need to start breaking before reaching
+ # top speed and before the next point (i.e. triangle shape velocity)
+ elif cur_point[0] + delta_x_to_max_speed + delta_x_to_stop_from_max_speed >= points[-1][0]:
+ # Add a new point at the point where we should start breaking
+ delta_t_to_next_x = compute_time_triangle(cur_point[0], points[-1][0], current_speed, 0, acceleration, deceleration)
+ next_x = cur_point[0] + current_speed*delta_t_to_next_x + 0.5*acceleration*delta_t_to_next_x**2
+ cur_time += delta_t_to_next_x
+ cur_point = [next_x, 0]
+ current_speed += delta_t_to_next_x*acceleration
+
+ # this is the case where we would reach max speed before the next point
+ # we need to create a new point where we would reach max speed
+ else:
+ # we would need to add a new point at max speed
+ cur_time += delta_t_to_max_speed
+ cur_point = [cur_point[0] + delta_x_to_max_speed, 0]
+ current_speed = max_speed
+
+ # This is the case where we are at max speed
+ # special functionality is that this block must
+ # add a point where we would need to start declerating to reach
+ # the final point
+ elif current_speed == max_speed:
+ next_point = points[cur_index+1]
+ # continue on with max speed
+
+ # add point to start decelerating
+ if next_point[0] + min_delta_x_stop >= points[-1][0]:
+ cur_time += (points[-1][0] - min_delta_x_stop - cur_point[0])/current_speed
+ cur_point = [points[-1][0] - min_delta_x_stop,0]
+ current_speed = max_speed
+ else:
+ # Continue on to next point
+ cur_time += (next_point[0] - cur_point[0])/current_speed
+ cur_point = next_point
+ cur_index += 1
+
+ # This is an edge case and should only be reach
+ # if the initial speed is greater than the max speed
+ elif current_speed > max_speed:
+ # We need to hit the breaks
+
+ next_point = points[cur_index+1]
+ # slow down to max speed
+ delta_t_to_max_speed = (current_speed - max_speed)/deceleration
+ delta_x_to_max_speed = current_speed*delta_t_to_max_speed - 0.5*deceleration*delta_t_to_max_speed**2
+
+ # If we would reach the next point before slowing down to max speed
+ # keep going until we reach the next point
+ if cur_point[0] + delta_x_to_max_speed >= next_point[0]:
+ delta_t_to_next_x = compute_time_to_x(cur_point[0], next_point[0], current_speed, -deceleration)
+ cur_time += delta_t_to_next_x
+ cur_point = [next_point[0], 0]
+ current_speed -= delta_t_to_next_x*deceleration
+ cur_index += 1
+ else:
+ # We would reach max speed before the next point
+ # we need to add a new point at the point where we
+ # would reach max speed
+ cur_time += delta_t_to_max_speed
+ cur_point = [cur_point[0] + delta_x_to_max_speed, 0]
+ current_speed = max_speed
+
+ else:
+ # not sure what falls here
+ raise ValueError("LONGITUDINAL PLAN ERROR: Not sure how we ended up here")
+
+ new_points.append(cur_point)
+ new_times.append(cur_time)
+ velocities.append(current_speed)
+
+ points = new_points
+ times = new_times
+ print("[PLAN] Computed points:", points)
+ print("[TIME] Computed time:", times)
+ print("[Velocities] Computed velocities:", velocities)
+
+ #=============================================
+
+ trajectory = Trajectory(path.frame,points,times,velocities)
+ return trajectory
+
+def compute_time_to_x(x0 : float, x1 : float, v : float, a : float) -> float:
+ """Computes the time to go from x0 to x1 with initial velocity v0 and final velocity v1
+ with constant acceleration a. I am assuming that we will always have a solution by settings
+ discriminant equal to zero, i'm not sure if this is an issue."""
+
+ """Consider changing the system to use linear operators instead of explicitly calculating because of instances here"""
+
+ t1 = (-v + max(0,(v**2 - 2*a*(x0-x1)))**0.5)/a
+ t2 = (-v - max(0,(v**2 - 2*a*(x0-x1)))**0.5)/a
+
+ if math.isnan(t1): t1 = 0
+ if math.isnan(t2): t2 = 0
+
+ valid_times = [n for n in [t1, t2] if n > 0]
+ if valid_times:
+ return min(valid_times)
+ else:
+ return 0.0
+
+def compute_time_triangle(x0 : float, xf: float, v0: float, vf : float, acceleration : float, deceleration : float) -> float:
+ """
+ Compute the time to go from current point assuming we are accelerating to the point at which
+ we would need to start breaking in order to reach the final point with velocity 0.
+ """
+ roots = quad_root(0.5*acceleration + acceleration**2/deceleration - 0.5*acceleration**2/deceleration,
+ v0+2*acceleration*v0/deceleration - acceleration*v0/deceleration,
+ x0 - xf + v0**2/deceleration - 0.5*v0**2/deceleration)
+ t1 = max(roots)
+ assert t1 > 0
+ return t1
+
+
+
+########################
+##### Rohit's Code #####
+########################
+def solve_for_v_peak(v0: float, acceleration: float, deceleration: float, total_length: float) -> float:
+
+ if acceleration <= 0 or deceleration <= 0:
+ raise ValueError("Acceleration and deceleration cant be negative")
+
+ #Formuala: (v_peak^2 - v0^2)/(2*a) + v_peak^2/(2*d) = total_length
+ numerator = deceleration * v0**2 + 2 * acceleration * deceleration * total_length
+ denominator = acceleration + deceleration
+ v_peak_sq = numerator / denominator
+
+ if v_peak_sq < 0:
+ return 0.0
+
+ return math.sqrt(v_peak_sq)
+
+
+def compute_dynamic_dt(acceleration, speed, k=0.01, a_min=0.5):
+ position_step = k * max(speed, 1.0) # Ensures position step is speed-dependent
+ return np.sqrt(2 * position_step / max(acceleration, a_min))
+
+
+def longitudinal_plan_dt(path, acceleration: float, deceleration: float, max_speed: float, current_speed: float):
+ # 1 parametrizatiom.
+ path_norm = path.arc_length_parameterize(speed=1.0)
+ total_length = path.length()
+
+ # -------------------
+ # If the path is too short, just return the path for preventing sudden halt of simulation
+ if total_length < 0.05:
+ points = [p for p in path_norm.points]
+ times = [t for t in path_norm.times]
+ return Trajectory(path.frame, points, times)
+ # -------------------
+
+ # 2. Compute distances for d_accel,d_decel
+ if max_speed > current_speed:
+ d_accel = (max_speed**2 - current_speed**2) / (2 * acceleration)
+ else:
+ d_accel = 0.0 # Already at or above max_speed
+
+ d_decel = (max_speed**2) / (2 * deceleration)
+
+ # 3. trapezoidal or triangle?
+ if d_accel + d_decel <= total_length:
+ t_accel = (max_speed - current_speed) / acceleration if max_speed > current_speed else 0.0
+ t_decel = max_speed / deceleration
+ d_cruise = total_length - d_accel - d_decel
+ t_cruise = d_cruise / max_speed if max_speed != 0 else 0.0
+ t_final = t_accel + t_cruise + t_decel
+ profile_type = "trapezoidal"
+ else:
+ # Triangular profile: not enough distance to reach max_speed so we will calculate peak speed.
+ peak_speed = solve_for_v_peak(current_speed, acceleration, deceleration, total_length)
+ # choose the min just in case
+ peak_speed = min(peak_speed, max_speed)
+ t_accel = (peak_speed - current_speed) / acceleration if peak_speed > current_speed else 0.0
+ t_decel = peak_speed / deceleration
+ t_final = t_accel + t_decel
+ profile_type = "triangular"
+
+ t = 0
+ times = []
+ s_vals = []
+ velocities = [] # for graphing and debugging purposes
+
+ num_time_steps = 0
+ speed = current_speed
+ while t < t_final:
+ times.append(t)
+ velocities.append(speed)
+ if profile_type == "trapezoidal":
+ if t < t_accel:
+ # Acceleration phase.
+ s = current_speed * t + 0.5 * acceleration * t**2
+ speed = current_speed + acceleration * t
+ elif t < t_accel + t_cruise:
+ # Cruise phase.
+ s = d_accel + max_speed * (t - t_accel)
+ else:
+ # Deceleration phase.
+ t_decel_phase = t - (t_accel + t_cruise)
+ s = total_length - 0.5 * deceleration * (t_decel - t_decel_phase)**2
+ speed = speed - deceleration * (t_decel-t_decel_phase)
+ else: # Triangular profile.
+ if t < t_accel:
+ # Acceleration phase.
+ s = current_speed * t + 0.5 * acceleration * t**2
+ speed = current_speed + acceleration * t
+ else:
+ t_decel_phase = t - t_accel
+ s_accel = current_speed * t_accel + 0.5 * acceleration * t_accel**2
+ s = s_accel + peak_speed * t_decel_phase - 0.5 * deceleration * t_decel_phase**2
+ speed = speed - deceleration * t_decel_phase
+
+ s_vals.append(min(s, total_length))
+ if s >= total_length:
+ break
+
+ dt = compute_dynamic_dt(acceleration if t < t_accel else deceleration,current_speed)
+ t = t + dt
+
+ num_time_steps +=1
+
+ # Compute trajectory points
+ points = [path_norm.eval(s) for s in s_vals]
+
+ trajectory = Trajectory(path_norm.frame, points, list(times),velocities=velocities)
+ return trajectory
+
+
+
+#########################
+##### Hansen's Code #####
+#########################
+def longitudinal_plan_dx(path : Path, acceleration : float, deceleration : float, max_speed : float, current_speed : float) -> Trajectory:
+ """Generates a longitudinal trajectory for a path with a
+ trapezoidal velocity profile.
+
+ 1. accelerates from current speed toward max speed
+ 2. travel along max speed
+ 3. if at any point you can't brake before hitting the end of the path,
+ decelerate with accel = -deceleration until velocity goes to 0.
+ """
+ path_normalized = path.arc_length_parameterize()
+ points = [p for p in path_normalized.points]
+ times = [t for t in path_normalized.times]
+
+ #=============================================
+ # Adjust these two numbers to choose between computation speed or smoothness
+ rq = 0.1 # Smaller, smoother
+ multi = 5 # Larger, smoother
+ print("-----LONGITUDINAL PLAN-----")
+ print("path length: ", path.length())
+ length = path.length()
+
+ # If the path is too short, just return the path for preventing sudden halt of simulation
+ if length < 0.05:
+ return Trajectory(path.frame, points, times)
+
+ # This assumes that the time denomination cannot be changed
+
+ # Starting point
+ x0 = points[0][0]
+ cur_point = points[0]
+ cur_time = times[0]
+ cur_index = 0
+ acc = 0
+
+ new_points = []
+ new_times = []
+ velocities = [] # for graphing and debugging purposes
+
+ while current_speed > 0 or cur_index == 0:
+ # we want to iterate through all the points and add them
+ # to the new points. However, we also want to add "critical points"
+ # where we reach top speed, begin decelerating, and stop
+ new_points.append(cur_point)
+ new_times.append(cur_time)
+ velocities.append(current_speed)
+ print("=====================================")
+ print("new points: ", new_points)
+ print("current index: ", cur_index)
+ print("current speed: ", current_speed)
+
+ # Information we will need:
+ # Calculate how much time it would take to stop
+ # Calculate how much distance it would take to stop
+ min_delta_t_stop = current_speed/deceleration
+ min_delta_x_stop = current_speed*min_delta_t_stop - 0.5*deceleration*min_delta_t_stop**2
+ assert min_delta_x_stop >= 0
+
+ # Check if we are done
+
+ # If we cannot stop before or stop exactly at the final position requested
+ if cur_point[0] + min_delta_x_stop >= points[-1][0] - 0.0001:
+ acc = deceleration
+ flag = 1
+ print("In case one")
+ # put on the breaks
+ # Calculate the next point in a special manner because of too-little time to stop
+ if cur_index >= len(points)-1:
+ # the next point in this instance would be when we stop
+ print(1)
+ if min_delta_x_stop < rq * acc:
+ next_point = (cur_point[0] + min_delta_x_stop, 0)
+ else:
+ next_point = (cur_point[0] + (min_delta_x_stop / (acc * multi)), 0)
+ flag = 0
+ else:
+ print(2)
+ next_point = points[cur_index+1]
+ if next_point[0] - cur_point[0] > rq * acc:
+ tmp = cur_point[0] + (next_point[0] - cur_point[0]) / (acc * multi)
+ flag = 0
+ next_point = [tmp, next_point[1]]
+
+ # keep breaking until the next milestone in path
+ print("continuing to next point")
+ delta_t_to_next_x = compute_time_to_x(cur_point[0], next_point[0], current_speed, -deceleration)
+ cur_time += delta_t_to_next_x
+ cur_point = next_point
+ current_speed -= deceleration*delta_t_to_next_x
+ if flag:
+ cur_index += 1
+
+ # This is the case where we are accelerating to max speed
+ # because the first if-statement covers for when we decelerating,
+ # the only time current_speed < max_speed is when we are accelerating
+ elif current_speed < max_speed:
+ print("In case two")
+ print(current_speed)
+ acc = acceleration
+ flag = 1
+ # next point
+ next_point = points[cur_index+1]
+ if next_point[0] - cur_point[0] > rq * acc:
+ tmp = cur_point[0] + (next_point[0] - cur_point[0]) / (acc * multi)
+ flag = 0
+ next_point = [tmp, next_point[1]]
+ # accelerate to max speed
+
+ # calculate the time it would take to reach max speed
+ delta_t_to_max_speed = (max_speed - current_speed)/acceleration
+ # calculate the distance it would take to reach max speed
+ delta_x_to_max_speed = current_speed*delta_t_to_max_speed + 0.5*acceleration*delta_t_to_max_speed**2
+
+ # if we would reach max speed after the next point,
+ # just move to the next point and update the current speed and time
+ if cur_point[0] + delta_x_to_max_speed >= next_point[0]:
+ print("go to next point")
+ # accelerate to max speed
+ delta_t_to_next_x = compute_time_to_x(cur_point[0], next_point[0], current_speed, acceleration)
+ cur_time += delta_t_to_next_x
+ cur_point = [next_point[0], 0]
+ current_speed += delta_t_to_next_x*acceleration
+ if flag:
+ cur_index += 1
+
+ # this is the case where we would reach max speed before the next point
+ # we need to create a new point where we would reach max speed
+ else:
+ print("adding new point")
+ # we would need to add a new point at max speed
+ cur_time += delta_t_to_max_speed
+ cur_point = [cur_point[0] + delta_x_to_max_speed, 0]
+ current_speed = max_speed
+
+ # This is the case where we are at max speed
+ # special functionality is that this block must
+ # add a point where we would need to start declerating to reach
+ # the final point
+ elif current_speed == max_speed:
+ next_point = points[cur_index+1]
+ # continue on with max speed
+ print("In case three")
+
+ # add point to start decelerating
+ if next_point[0] + min_delta_x_stop >= points[-1][0]:
+ print("Adding new point to start decelerating")
+ cur_time += (points[-1][0] - min_delta_x_stop - cur_point[0])/current_speed
+ cur_point = [points[-1][0] - min_delta_x_stop,0]
+ current_speed = max_speed
+ else:
+ # Continue on to next point
+ print("Continuing on to next point")
+ cur_time += (next_point[0] - cur_point[0])/current_speed
+ cur_point = next_point
+ cur_index += 1
+
+ # This is an edge case and should only be reach
+ # if the initial speed is greater than the max speed
+ elif current_speed > max_speed:
+ # We need to hit the breaks
+ acc = deceleration
+ flag = 1
+ # next point
+ next_point = points[cur_index+1]
+ if next_point[0] - cur_point[0] > rq * acc:
+ tmp = cur_point[0] + (next_point[0] - cur_point[0]) / (acc * multi)
+ flag = 0
+ next_point = [tmp, next_point[1]]
+ print("In case four")
+ # slow down to max speed
+ delta_t_to_max_speed = (current_speed - max_speed)/deceleration
+ delta_x_to_max_speed = current_speed*delta_t_to_max_speed - 0.5*deceleration*delta_t_to_max_speed**2
+
+ # If we would reach the next point before slowing down to max speed
+ # keep going until we reach the next point
+ if cur_point[0] + delta_x_to_max_speed >= next_point[0]:
+ delta_t_to_next_x = compute_time_to_x(cur_point[0], next_point[0], current_speed, -deceleration)
+ cur_time += delta_t_to_next_x
+ cur_point = [next_point[0], 0]
+ current_speed -= delta_t_to_next_x*deceleration
+ cur_index += 1
+ else:
+ # We would reach max speed before the next point
+ # we need to add a new point at the point where we
+ # would reach max speed
+ cur_time += delta_t_to_max_speed
+ cur_point = [cur_point[0] + delta_x_to_max_speed, 0]
+ current_speed = max_speed
+
+ else:
+ # not sure what falls here
+ raise ValueError("LONGITUDINAL PLAN ERROR: Not sure how we ended up here")
+
+ new_points.append(cur_point)
+ new_times.append(cur_time)
+ velocities.append(current_speed)
+
+ points = new_points
+ times = new_times
+ print("[PLAN] Computed points:", points)
+ print("[TIME] Computed time:", times)
+ print("[Velocities] Computed velocities:", velocities)
+
+ #=============================================
+
+ trajectory = Trajectory(path.frame,points,times)
+ return trajectory
+
+def longitudinal_brake(path : Path, deceleration : float, current_speed : float) -> Trajectory:
+ """Generates a longitudinal trajectory for braking along a path."""
+ path_normalized = path.arc_length_parameterize()
+ points = [p for p in path_normalized.points]
+ times = [t for t in path_normalized.times]
+
+ #=============================================
+
+ print("=====LONGITUDINAL BRAKE=====")
+ print("path length: ", path.length())
+ length = path.length()
+
+ x0 = points[0][0]
+ t_stop = current_speed / deceleration
+ x_stop = x0 + current_speed * t_stop - 0.5 * deceleration * t_stop**2
+
+ new_points = []
+ velocities = []
+
+ for t in times:
+ if t <= t_stop:
+ x = x0 + current_speed * t - 0.5 * deceleration * t**2
+ else:
+ x = x_stop
+ new_points.append([x, 0])
+ velocities.append(current_speed - deceleration * t)
+ points = new_points
+ print("[BRAKE] Computed points:", points)
+
+ #=============================================
+
+ trajectory = Trajectory(path.frame,points,times,velocities)
+ return trajectory
+
+
+
+################################################################################
+########## Yield Trajectory Planner ############################################
+################################################################################
+
+#####################################################
+##### Patrick, Animesh, Henry, and Yudai's Code #####
+#####################################################
+class YieldTrajectoryPlanner(Component):
+ """Follows the given route. Brakes if you have to yield or
+ you are at the end of the route, otherwise accelerates to
+ the desired speed.
+ """
+
+ def __init__(self):
+ self.route_progress = None
+ self.t_last = None
+
+ self.mode = settings.get("planning.longitudinal_plan.mode")
+ self.planner = settings.get("planning.longitudinal_plan.planner")
+ self.acceleration = settings.get("planning.longitudinal_plan.acceleration")
+ self.deceleration = settings.get("planning.longitudinal_plan.deceleration")
+ self.desired_speed = settings.get("planning.longitudinal_plan.desired_speed")
+ self.yield_deceleration = settings.get("planning.longitudinal_plan.yield_deceleration")
+
+ def state_inputs(self):
+ return ['all']
+
+ def state_outputs(self) -> List[str]:
+ return ['trajectory']
+
+ def rate(self):
+ return 10.0
+
+ def update(self, state : AllState):
+ vehicle = state.vehicle # type: VehicleState
+ route = state.route # type: Route
+ t = state.t
+
+ if self.t_last is None:
+ self.t_last = t
+ dt = t - self.t_last
+ print("Elapsed time:", int(dt*1000), "ms")
+ self.t_last = t
+
+ curr_x = vehicle.pose.x
+ curr_y = vehicle.pose.y
+ curr_v = vehicle.v
+
+ #figure out where we are on the route
+ if self.route_progress is None:
+ self.route_progress = 0.0
+ closest_dist,closest_parameter = state.route.closest_point_local((curr_x,curr_y),[self.route_progress-5.0,self.route_progress+5.0])
+ self.route_progress = closest_parameter
+
+ # Compute the lookahead distance
+ lookahead_distance = max(10, curr_v**2 / (2 * self.yield_deceleration))
+ print("Lookahead distance:", lookahead_distance)
+ route_with_lookahead = route.trim(closest_parameter,closest_parameter + lookahead_distance)
+
+ # Default values
+ should_brake = False
+ input_values = [{"decel": self.deceleration, "desired_speed": self.desired_speed, "collision_distance": lookahead_distance}]
+
+ # Extract yielding information from all YIELDING agents.
+ for r in state.relations:
+ if r.type == EntityRelationEnum.YIELDING and r.obj1 == '':
+ input_values.append({"decel": r.yield_decel, "desired_speed": r.yield_speed, "collision_distance": r.yield_dist})
+
+ print("Input values:", input_values)
+ # Choose minimum desired speed and extract deceleration and collision distance from input_values.
+ valid_input_values = [val for val in input_values if val['desired_speed'] is not None]
+ desired_speed = min(valid_input_values, key=lambda x: x['desired_speed'])['desired_speed'] if not None else self.desired_speed
+ decel = min(valid_input_values, key=lambda x: x['desired_speed'])['decel'] if not None else self.deceleration
+ # If desired_speed is 0, we should brake to stop.
+ if desired_speed == 0.0:
+ should_brake = True
+ else:
+ collision_distance = min(valid_input_values, key=lambda x: x['desired_speed'])['collision_distance'] if not None else lookahead_distance
+ # Update the lookahead distance to pedestrian.
+ route_with_lookahead = route.trim(closest_parameter,closest_parameter + collision_distance)
+ print(f"Collision distance: {collision_distance:.2f} m")
+
+ print(f"Desired speed: {desired_speed:.2f} m/s")
+ print(f"Deceleration: {decel:.2f} m/s^2")
+
+ should_accelerate = (not should_brake and curr_v < self.desired_speed)
+
+ #choose whether to accelerate, brake, or keep at current velocity
+ if should_accelerate:
+ traj = longitudinal_plan(route_with_lookahead, self.acceleration, decel, desired_speed, curr_v, self.planner)
+ elif should_brake:
+ traj = longitudinal_brake(route_with_lookahead, decel, curr_v)
+ else:
+ traj = longitudinal_plan(route_with_lookahead, 0.0, decel, desired_speed, curr_v, self.planner)
+
+ return traj
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..ca905c876 100644
--- a/GEMstack/onboard/planning/pure_pursuit.py
+++ b/GEMstack/onboard/planning/pure_pursuit.py
@@ -8,6 +8,7 @@
from ..interface.gem import GEMVehicleCommand
from ..component import Component
import numpy as np
+import rospy
class PurePursuit(object):
"""Implements a pure pursuit controller on a second-order Dubins vehicle."""
@@ -19,6 +20,7 @@ def __init__(self, lookahead = None, lookahead_scale = None, crosstrack_gain = N
self.wheelbase = settings.get('vehicle.geometry.wheelbase')
self.wheel_angle_range = [settings.get('vehicle.geometry.min_wheel_angle'),settings.get('vehicle.geometry.max_wheel_angle')]
self.steering_angle_range = [settings.get('vehicle.geometry.min_steering_angle'),settings.get('vehicle.geometry.max_steering_angle')]
+ # self.launch_control = settings.get('control.pure_pursuit.launch_control')
if desired_speed is not None:
self.desired_speed_source = desired_speed
@@ -35,6 +37,10 @@ def __init__(self, lookahead = None, lookahead_scale = None, crosstrack_gain = N
#if trajectory = None, then only an untimed path was provided and we can't use the path velocity as the reference
self.trajectory = None # type: Trajectory
+ self.enable_launch_control = settings.get('control.launch_control.enable', False)
+ self.stage_duration = settings.get('control.launch_control.stage_duration', 0.5)
+ self.launch_start_time = None
+
self.current_path_parameter = 0.0
self.current_traj_parameter = 0.0
self.t_last = None
@@ -45,7 +51,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
@@ -90,6 +96,7 @@ def compute(self, state : VehicleState, component : Component = None):
#TODO: calculate parameter that is look_ahead distance away from the closest point?
#(rather than just advancing the parameter)
des_parameter = closest_parameter + self.look_ahead + self.look_ahead_scale * speed
+ print("desired speed source is:", self.desired_speed_source)
print("Closest parameter: " + str(closest_parameter),"distance to path",closest_dist)
if closest_dist > 0.1:
print("Closest point",self.path.eval(closest_parameter),"vs",(curr_x,curr_y))
@@ -162,12 +169,46 @@ def compute(self, state : VehicleState, component : Component = None):
print("Desired speed",desired_speed,"m/s",", trying to reach desired",next_desired_speed,"m/s")
feedforward_accel= np.clip(feedforward_accel, -self.max_decel, self.max_accel)
print("Feedforward accel: " + str(feedforward_accel) + " m/s^2")
+ elif self.desired_speed_source == 'racing':
+ # get radius of the upcoming curve_points
+ # right now we can only use 3 points
+ curve_points = 3
+ curve_radius = self.path.fit_curve_radius((curr_x,curr_y), curve_points)
+ # map curve radius to desired_speed. Note curve_radius can be inf if all points are colinear
+ print("curve_radius: ", curve_radius)
+ #if curve_radius < 10:
+ # desired_speed = 2.5
+ #elif curve_radius < 15:
+ # desired_speed = 3
+ #elif curve_radius < 20:
+ # desired_speed = 4
+ #elif curve_radius < 30:
+ # desired_speed = 5
+ #else:
+ # desired_speed = 10
+ desired_speed = (.5*curve_radius)**.5
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
+
+
+ # # # braking for 50m dash test
+ # if self.current_path_parameter >= self.path.domain()[1]:
+ # if component is not None:
+ # component.debug_event('Past the end of trajectory')
+ # #past the end, just stop
+ # desired_speed = 0.0
+ # feedforward_accel = -3.0
+ # f_delta = 0
+
+
output_accel = self.pid_speed.advance(e = desired_speed - speed, t = t, feedforward_term=feedforward_accel)
+
+ # self.brake_cmd.f64_cmd = maxbrake
+ # self.accel_cmd.f64_cmd = 0
+
if component is not None:
component.debug('curr pt',(curr_x,curr_y))
component.debug('curr param',self.current_path_parameter)
@@ -178,6 +219,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 +230,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)
@@ -194,6 +242,8 @@ class PurePursuitTrajectoryTracker(Component):
def __init__(self,vehicle_interface=None, **args):
self.pure_pursuit = PurePursuit(**args)
self.vehicle_interface = vehicle_interface
+ self.enable_launch_control = settings.get('control.launch_control.enable', False) # and vehicle.v < 0.1
+ self.stage_duration = settings.get('control.launch_control.stage_duration', 0.5)
def rate(self):
return 50.0
@@ -210,7 +260,27 @@ def update(self, vehicle : VehicleState, trajectory: Trajectory):
#print("Desired wheel angle",wheel_angle)
steering_angle = np.clip(front2steer(wheel_angle), self.pure_pursuit.steering_angle_range[0], self.pure_pursuit.steering_angle_range[1])
#print("Desired steering angle",steering_angle)
- self.vehicle_interface.send_command(self.vehicle_interface.simple_command(accel,steering_angle, vehicle))
+
+ cmd = self.vehicle_interface.simple_command(accel, steering_angle, vehicle)
+
+ if self.enable_launch_control:
+ print("launch control active")
+ if not hasattr(self,'_launch_start_time'):
+ self._launch_start_time = rospy.get_time()
+ elapsed = rospy.get_time() - self._launch_start_time
+ if elapsed < self.stage_duration:
+ cmd.accelerator_pedal_position = 0.0
+ cmd.brake_pedal_position = 1.0
+ elif elapsed < 2 * self.stage_duration:
+ cmd.accelerator_pedal_position = 1.0
+ cmd.brake_pedal_position = 1.0
+ elif elapsed < 3 * self.stage_duration:
+ cmd.accelerator_pedal_position = 1.0
+ cmd.brake_pedal_position = 0.0
+ else:
+ self.enable_launch_control = False
+
+ self.vehicle_interface.send_command(cmd)
def healthy(self):
return self.pure_pursuit.path is not None
\ No newline at end of file
diff --git a/GEMstack/onboard/planning/racing_planning.py b/GEMstack/onboard/planning/racing_planning.py
new file mode 100644
index 000000000..8524d4946
--- /dev/null
+++ b/GEMstack/onboard/planning/racing_planning.py
@@ -0,0 +1,1037 @@
+from ...state.trajectory import Trajectory
+from ...state.vehicle import VehicleState
+from ...state import AgentState, AgentEnum
+from ..component import Component
+
+from ...state.trajectory import Trajectory, compute_headings, Path
+from ...state.physical_object import ObjectFrameEnum
+
+import numpy as np
+import matplotlib.pyplot as plt
+from scipy.optimize import minimize
+
+from typing import Dict
+
+# --------------------------
+# This is the main code for the racing trajectory planner.
+# Contributors: Hua-Ta, Shilan
+# --------------------------
+
+def scenario_check(vehicle_state, cone_state):
+ """
+ Check the cone state and determine the scenario.
+ Args:
+ vehicle_state: The state of the vehicle.
+ cone_state: The state of the cones.
+ Returns:
+ str: The scenario type.
+ - 'left_pass': cone pointed left, go left
+ - 'right_pass': cone pointed right, go right
+ - 'u_turn': cone standing up, make a U-turn
+ tuple: (cone_x, cone__y)
+ """
+ # Get the closest cone info
+ cones_ahead = sorted(cone_state, key=lambda c: np.linalg.norm(
+ np.array([c['x'], c['y']]) - np.array(vehicle_state['position'])))
+ cone_direction = cones_ahead[0]['orientation']
+ cone_position = (cones_ahead[0]['x'], cones_ahead[0]['y'])
+
+ # Check the cone orientation
+ if cone_direction != 'LEFT' and cone_direction != 'RIGHT' and cone_direction != 'STANDING' and cone_direction != '90turn':
+ raise ValueError("Unknown cone orientation")
+
+ return cone_direction, cone_position
+
+def waypoint_generate(vehicle_state, cones, cone_idx):
+ """
+ Generate waypoints based on the scenario.
+ Args:
+ vehicle_state: The state of the vehicle.
+ cone_state: The state of the cones.
+ Returns:
+ Tuple[str, Tuple[float, float], Tuple[float, float]]:
+ scenario: detected scenario type
+ flex_wp: flexible waypoint (used to maneuver)
+ fixed_wp: fixed waypoint (goal position)
+ """
+ scenario, cone_position = scenario_check(vehicle_state, [cones[cone_idx]])
+ car_position = np.array(vehicle_state['position'])
+ car_heading = vehicle_state['heading'] # in radians
+ current_heading = car_heading
+ target_heading = car_heading
+
+ # ===== Parameters =====
+ u_turn_radius = 11.5 # Radius for U-turn
+ offset = 2.0 # Offset for left/right pass
+ lookahead_distance = 10.0 # Distance ahead for fixed point
+ # ======================
+
+ # Direction vector based on heading
+ heading_vector = np.array([np.cos(car_heading), np.sin(car_heading)])
+
+ # Vector perpendicular to heading (to determine left/right)
+ perpendicular_vector = np.array([-np.sin(car_heading), np.cos(car_heading)])
+
+ if cone_idx > 0:
+ prev_cone_position = np.array((cones[cone_idx - 1]['x'], cones[cone_idx - 1]['y']))
+ cone_position = np.array((cones[cone_idx]['x'], cones[cone_idx]['y']))
+ target_heading = np.arctan2(cone_position[1] - prev_cone_position[1],
+ cone_position[0] - prev_cone_position[0])
+
+ if scenario == 'STANDING':
+ # U-turn: Generate points in a semi-circular arc around the cone
+ cone = np.array(cone_position)
+
+ # Number of waypoints to generate for the arc
+ num_arc_points = 9
+
+ # Generate waypoints in a smooth semi-circular pattern on the RIGHT side
+ flex_wps_list = []
+
+ # Create a semi-circular arc from 0 to π
+ # But negate perpendicular_vector to go to the right side
+ for i in range(num_arc_points):
+ # Calculate angle in the semi-circle (0 to π)
+ angle = i * np.pi * 1 / (num_arc_points - 1)
+
+ # MODIFIED: Negative perpendicular_vector to go to right side of cone
+ # This creates a counter-clockwise turn around the cone
+ wp = cone - u_turn_radius * (
+ perpendicular_vector * np.cos(angle) -
+ heading_vector * np.sin(angle)
+ )
+
+ flex_wps_list.append(wp)
+
+ # Fixed waypoint: behind the cone after U-turn (also on right side)
+ fixed_wp = cone + u_turn_radius * perpendicular_vector
+
+ target_heading = target_heading + np.pi
+
+ # For visualization only
+ # for i, wp in enumerate(flex_wps_list):
+ # plt.plot(wp[0], wp[1], 'ro') # Plot all waypoints in red
+ # plt.text(wp[0], wp[1], f'wp{i}', fontsize=9)
+
+ # plt.plot(fixed_wp[0], fixed_wp[1], 'bo') # Plot fixed waypoint in blue
+ # plt.plot(cone[0], cone[1], 'gx') # Plot cone in green
+ # plt.plot(car_position[0], car_position[1], 'ks') # Plot car position
+ # plt.axis('equal') # Equal aspect ratio for better visualization
+ # plt.grid(True)
+ # plt.show()
+
+ elif scenario == 'LEFT':
+ cone = np.array(cone_position)
+
+ # Flexible waypoint: go to the left of the cone
+ flex_wp1 = cone + offset * perpendicular_vector
+ flex_wps_list = [flex_wp1]
+
+ # Fixed waypoint: forward after passing the cone
+ # fixed_wp = flex_wp + heading_vector * lookahead_distance - offset * perpendicular_vector * 2
+ fixed_wp = flex_wp1 + heading_vector * lookahead_distance - offset * perpendicular_vector
+
+ elif scenario == 'RIGHT':
+ cone = np.array(cone_position)
+
+ # Flexible waypoint: go to the right of the cone
+ flex_wp1 = cone - offset * perpendicular_vector
+ flex_wps_list = [flex_wp1]
+
+ # Fixed waypoint: forward after passing the cone
+ # fixed_wp = flex_wp + heading_vector * lookahead_distance + offset * perpendicular_vector * 2
+ fixed_wp = flex_wp1 + heading_vector * lookahead_distance + offset * perpendicular_vector
+
+ # TODO: move to a different setting instead of as a scenario
+ elif scenario == '90turn':
+ turn_vector = np.array([-np.sin(car_heading + np.pi / 6), np.cos(car_heading + np.pi / 6)])
+ cone = np.array(cone_position)
+ distance_to_cone = np.linalg.norm(car_position - cone)
+
+ flex_wps_list = []
+ if distance_to_cone > 7:
+ steps = int(distance_to_cone // 6)
+ print("steps:", steps)
+
+ final_flex_wp = cone + 1.0 * perpendicular_vector + heading_vector * 1.0
+ fixed_wp = cone - turn_vector * 2.5 + heading_vector * 0.0
+
+ cone_direction = (final_flex_wp - car_position) / np.linalg.norm(final_flex_wp - car_position)
+ for i in range(steps - 2):
+ intermediate_wp = car_position + cone_direction * ((i + 1) * 6)
+ flex_wps_list.append(intermediate_wp)
+
+ flex_wps_list.append(final_flex_wp)
+ else:
+ flex_wp = cone + 1.0 * perpendicular_vector + heading_vector * 1.0
+ fixed_wp = cone - turn_vector * 2.5 + heading_vector * 0.0
+ flex_wps_list = [flex_wp]
+
+ else:
+ flex_wps_list = None
+ fixed_wp = None
+
+ target_heading = (target_heading + np.pi) % (2 * np.pi) - np.pi
+ current_heading = (current_heading + np.pi) % (2 * np.pi) - np.pi
+
+ if abs(target_heading - current_heading) > np.pi:
+ if target_heading < current_heading:
+ target_heading += 2 * np.pi
+ else:
+ target_heading -= 2 * np.pi
+
+ return scenario, flex_wps_list, fixed_wp, target_heading
+
+def trajectory_generation(init_state, final_state, N=30, T=0.1, Lr=1.5,
+ w_c=10.0, w_eps=0.0, w_vvar=4.0,
+ w_terminal=10.0,
+ v_min=3.0, v_max=11.0,
+ waypoints=None, waypoint_penalty_weight=100.0):
+ """
+ Generate a dynamically feasible trajectory between init_state and final_state
+ using curvature-based vehicle dynamics and nonlinear optimization.
+
+ Now supports multiple waypoints.
+
+ Parameters:
+ - init_state (dict): Initial vehicle state with keys 'x', 'y', 'psi', 'c', 'v'.
+ - final_state (dict): Target vehicle state with keys 'x', 'y', 'psi', 'c'.
+ - N (int): Number of discrete time steps in the trajectory.
+ - T (float): Duration of each time step (in seconds).
+ - Lr (float): Distance from the vehicle's center to the rear axle.
+ - w_c (float): Weight for penalizing curvature (smoothness of turns).
+ - w_eps (float): Weight for penalizing curvature rate (reduces sharp steering changes).
+ - w_vvar (float): Weight for penalizing speed variance (encourages speed smoothness).
+ - w_terminal (float): Weight for penalizing final state deviation (soft constraint).
+ - v_min (float): Minimum allowed speed (in m/s).
+ - v_max (float): Maximum allowed speed (in m/s).
+ - waypoints (list or None): Optional list of (x, y) coordinates that the trajectory should pass near.
+ - waypoint_penalty_weight (float): Penalty weight for distance from waypoints (soft constraint).
+
+ Returns:
+ - x, y, psi, c, v, eps (np.ndarray): Arrays of optimized state and control values.
+ - final_error (dict): Final state errors in x, y, psi, and c.
+ """
+ def cost(p):
+ x_, y_, psi_, c_, v_, eps_ = np.split(p, [N - 1, 2 * (N - 1), 3 * (N - 1), 4 * (N - 1), 5 * (N - 1)])
+ c_seq = np.concatenate(([init_state['c']], c_))
+ v_seq = np.concatenate(([init_state['v']], v_))
+ x_final, y_final, psi_final, c_final = x_[-1], y_[-1], psi_[-1], c_[-1]
+
+ cost_c = w_c * np.sum(c_seq ** 2)
+ cost_eps = w_eps * np.sum(eps_ ** 2)
+ v_mean = np.mean(v_seq)
+ cost_vvar = w_vvar * np.mean((v_seq - v_mean) ** 2)
+
+ cost_terminal = w_terminal * (
+ (x_final - final_state['x']) ** 2 +
+ (y_final - final_state['y']) ** 2 +
+ (psi_final - final_state['psi']) ** 2 * 100 +
+ (c_final - final_state['c']) ** 2 * 100
+ )
+
+ cost_waypoints = 0.0
+ if waypoints is not None and len(waypoints) > 0:
+ # Calculate equally spaced indices for each waypoint
+ num_waypoints = len(waypoints)
+ indices = [int((i + 1) * (N - 1) / (num_waypoints + 1)) for i in range(num_waypoints)]
+
+ # Sum penalties for each waypoint at its corresponding index
+ for wp_idx, waypoint in enumerate(waypoints):
+ traj_idx = indices[wp_idx]
+ cost_waypoints += waypoint_penalty_weight * (
+ (x_[traj_idx] - waypoint[0])**2 + (y_[traj_idx] - waypoint[1])**2
+ )
+
+ return cost_c + cost_eps + cost_vvar + cost_terminal + cost_waypoints
+ def dynamics_constraints(p):
+ x_, y_, psi_, c_, v_, eps_ = np.split(p, [N - 1, 2 * (N - 1), 3 * (N - 1), 4 * (N - 1), 5 * (N - 1)])
+ constraints = []
+ x_prev, y_prev, psi_prev, c_prev, v_prev = init_state['x'], init_state['y'], init_state['psi'], init_state['c'], init_state['v']
+ for k in range(N - 1):
+ dx = v_prev * np.cos(psi_prev + c_prev * Lr) * T
+ dy = v_prev * np.sin(psi_prev + c_prev * Lr) * T
+ dpsi = v_prev * c_prev * T
+ dc = eps_[k] * T
+ constraints.extend([
+ x_[k] - (x_prev + dx),
+ y_[k] - (y_prev + dy),
+ psi_[k] - (psi_prev + dpsi),
+ c_[k] - (c_prev + dc)
+ ])
+ x_prev, y_prev, psi_prev, c_prev, v_prev = x_[k], y_[k], psi_[k], c_[k], v_[k]
+ return constraints
+
+ # Initial guesses
+ x_vals = np.linspace(init_state['x'], final_state['x'], N)
+ y_vals = np.linspace(init_state['y'], final_state['y'], N)
+ psi_vals = np.linspace(init_state['psi'], final_state['psi'], N)
+ c_vals = np.linspace(init_state['c'], final_state['c'], N)
+ v_vals = np.ones(N) * init_state['v']
+ eps_vals = np.zeros(N - 1)
+
+ p0 = np.concatenate([x_vals[1:], y_vals[1:], psi_vals[1:], c_vals[1:], v_vals[1:], eps_vals])
+ bounds = [(None, None)] * (4 * (N - 1)) + [(v_min, v_max)] * (N - 1) + [(None, None)] * (N - 1)
+
+ result = minimize(cost, p0, bounds=bounds,
+ constraints={'type': 'eq', 'fun': dynamics_constraints},
+ options={'maxiter': 1000})
+ if not result.success:
+ raise RuntimeError("Optimization failed")
+
+ x_, y_, psi_, c_, v_, eps_ = np.split(result.x, [N - 1, 2 * (N - 1), 3 * (N - 1), 4 * (N - 1), 5 * (N - 1)])
+ x_full = np.concatenate(([init_state['x']], x_))
+ y_full = np.concatenate(([init_state['y']], y_))
+ psi_full = np.concatenate(([init_state['psi']], psi_))
+ c_full = np.concatenate(([init_state['c']], c_))
+ v_full = np.concatenate(([init_state['v']], v_))
+
+ final_error = {
+ 'x_error': abs(x_full[-1] - final_state['x']),
+ 'y_error': abs(y_full[-1] - final_state['y']),
+ 'psi_error': abs(psi_full[-1] - final_state['psi']),
+ 'c_error': abs(c_full[-1] - final_state['c']),
+ }
+
+ return x_full, y_full, psi_full, c_full, v_full, eps_, final_error
+
+def feasibility_check(trajectory, cone_map, car_width=2.0, safety_margin=0.3, v=10.0, Lr=1.5, T=0.1):
+ """
+ Check if the car trajectory collides with any cones.
+
+ Parameters:
+ - trajectory: list of (y, psi, c) states
+ - cone_map: list of (x, y) cone positions
+ - car_width: width of the vehicle in meters
+ - safety_margin: buffer around the vehicle
+ - v: vehicle constant speed (used for x position estimation)
+ - Lr: distance to rear axle
+ - T: time step
+
+ Returns:
+ - feasible: True if no collisions
+ - collisions: list of indices of cones that were collided with (for plotting purpose)
+ - x_vals, y_vals: trajectory positions for plotting (for plotting purpose)
+ """
+ y_vals, psi_vals, c_vals = zip(*trajectory)
+ x_vals = [0.0]
+ for i in range(1, len(trajectory)):
+ dx = v * np.cos(psi_vals[i-1] + c_vals[i-1] * Lr) * T
+ x_vals.append(x_vals[-1] + dx)
+
+ collision_radius = (car_width / 2.0) + safety_margin
+ collisions = []
+
+ for j, (cone_x, cone_y) in enumerate(cone_map):
+ for x, y in zip(x_vals, y_vals):
+ if np.hypot(x - cone_x, y - cone_y) < collision_radius:
+ collisions.append(j)
+ break
+
+ feasible = len(collisions) == 0
+ return feasible, collisions, x_vals, y_vals
+
+
+def waypoint_search_optimization(vehicle_state, cones, search_attempts=3):
+ valid_flex_wps = []
+ valid_fixed_wps = []
+ current_state = vehicle_state.copy()
+ cones_copy = cones.copy()
+
+ for i in range(min(search_attempts, len(cones_copy))):
+ scenario, flex_wps, fixed_wp = waypoint_generate(current_state, cones_copy)
+
+ if flex_wps is None or fixed_wp is None:
+ break
+
+ for flex_wp in flex_wps:
+ init_state = {
+ 'x': current_state['position'][0],
+ 'y': current_state['position'][1],
+ 'psi': current_state['heading'],
+ 'c': 0.0,
+ 'v': current_state['velocity']
+ }
+ final_state = {
+ 'x': fixed_wp[0],
+ 'y': fixed_wp[1],
+ 'psi': current_state['heading'],
+ 'c': 0.0
+ }
+
+ try:
+ x, y, psi, c, v, eps, final_error = trajectory_generation(init_state, final_state, waypoint=flex_wp)
+ trajectory = list(zip(y, psi, c))
+ feasible, collisions, x_vals, y_vals = feasibility_check(trajectory, [(cone['x'], cone['y']) for cone in cones])
+ # print(f"Checking waypoint: {flex_wp}, Fixed: {fixed_wp}, Feasible: {feasible}, Collisions: {collisions}")
+ if feasible:
+ valid_flex_wps.append(flex_wp)
+ valid_fixed_wps.append(fixed_wp)
+ current_state['position'] = list(fixed_wp)
+ break
+ except:
+ continue
+ if len(cones_copy) > 0:
+ cones_copy.pop(0)
+ return valid_flex_wps, valid_fixed_wps
+
+
+def to_gemstack_trajectory(x_all, y_all, v_all, T=0.1):
+ t_vals = np.arange(len(x_all)) * T
+ combined_xy = [[x, y] for x, y in zip(x_all, y_all)]
+ curr_path = Path(ObjectFrameEnum.START,combined_xy)
+ path = compute_headings(curr_path)
+ path_normalized = path.arc_length_parameterize()
+ points = [p for p in path_normalized.points]
+ return Trajectory(points=points, times=t_vals, frame=ObjectFrameEnum.START)
+
+
+def plan_full_slalom_trajectory(vehicle_state, cones):
+ x_all, y_all, v_all = [], [], []
+ current_pos = np.array(vehicle_state['position'])
+ current_heading = vehicle_state['heading']
+
+ for cone_idx, cone in enumerate(cones):
+ scenario, flex_wps, fixed_wp, target_heading = waypoint_generate(vehicle_state, cones, cone_idx)
+ print(f"Scenario: {scenario}, Cone: {cone}, Flex WP: {flex_wps}, Fixed WP: {fixed_wp}")
+ if not flex_wps or fixed_wp is None:
+ continue
+ # flex_wp = flex_wps[0]
+ current_heading = (current_heading + np.pi) % (2 * np.pi) - np.pi
+
+ init_state = {
+ 'x': current_pos[0], 'y': current_pos[1], 'psi': current_heading,
+ 'c': 0.0, 'v': vehicle_state['velocity']
+ }
+ final_state = {
+ 'x': fixed_wp[0], 'y': fixed_wp[1], 'psi': target_heading, 'c': 0.0
+ }
+
+ x, y, psi, c, v, eps, _ = trajectory_generation(init_state, final_state, waypoints=flex_wps)
+ x_all.extend(x)
+ y_all.extend(y)
+ v_all.extend(v)
+
+ current_pos = np.array([x[-1], y[-1]])
+ current_heading = psi[-1]
+ current_steering = c[-1]
+
+ vehicle_state = {
+ 'position': current_pos,
+ 'heading': current_heading,
+ 'velocity': v[-1]
+ }
+ current_pos = np.array([x[-1], y[-1]])
+
+ # # Plot overall trajectory
+ # plt.figure()
+ # plt.plot(x_all, y_all, label='Overall Trajectory')
+
+ # # Plot cones
+ # for i, cone in enumerate(cones):
+ # plt.scatter(cone['x'], cone['y'], color='orange', s=10, label='Cone' if i == 0 else "")
+ # plt.text(cone['x'], cone['y'] + 0.5, f'C{i+1}', ha='center', fontsize=9, color='darkorange')
+
+ # plt.title('4-Cone Full Course Trajectory')
+ # plt.xlabel('X')
+ # plt.ylabel('Y')
+ # plt.legend()
+ # plt.axis('equal')
+ # plt.grid(True)
+ # plt.show()
+
+ combined_xy = [[x, y] for x, y in zip(x_all, y_all)]
+ # print(combined_xy)
+ path = Path(ObjectFrameEnum.START,combined_xy)
+ path = compute_headings(path)
+ path = path.arc_length_parameterize()
+ # print(path)
+ return path.racing_velocity_profile()
+ # return to_gemstack_trajectory(x_all, y_all, v_all)
+
+
+def no_cone_planning(vehicle_dict):
+ temp_points = []
+ vehicle_x, vehicle_y = vehicle_dict['position'][0], vehicle_dict['position'][1]
+ vehicle_heading = vehicle_dict['heading']
+ vehicle_velocity = vehicle_dict['velocity']
+ step_size = 0.5 * (max(1,vehicle_velocity))
+ for i in range(10):
+ temp_points.append([vehicle_x + i * step_size * np.cos(vehicle_heading),
+ vehicle_y + i * step_size * np.sin(vehicle_heading)])
+
+ path = Path(ObjectFrameEnum.START,temp_points)
+ # print(temp_points)
+ path = compute_headings(path)
+ path = path.arc_length_parameterize()
+ # print(path)
+ return path.racing_velocity_profile()
+
+def got_new_cone(current_cones, prev_cones):
+ if current_cones is None:
+ return False
+ if prev_cones is None:
+ return True
+ prev_ids = {cone['id'] for cone in prev_cones}
+
+ for cone in current_cones:
+ if cone['id'] not in prev_ids:
+ return True # Found a new cone not in previous list
+
+ return False
+################################################
+# Main Racing Trajectory Planner Class
+################################################
+class SlalomTrajectoryPlanner(Component):
+ def __init__(self, **kwargs):
+ # You can accept args here if needed
+ self.trajectory = None
+ self.prev_cones = None
+ # ----------------------------
+ # Predifined-Cones Simulation
+ # self.run_fake_plan = True
+ # self.onboard = False
+
+ # # Onboard
+ self.run_fake_plan = False
+ self.onboard = True
+ # ----------------------------
+
+ self.DEBUG_MODE = True
+
+ def state_inputs(self):
+ return ['agents', 'vehicle'] # Receive VehicleState & AgentState input
+
+ def state_outputs(self):
+ return ['trajectory'] # Return trajectory output
+
+ def rate(self): # Setup the update rate
+ return 1.0
+
+ def update(self, agents: Dict[str, AgentState], vehicle: VehicleState):
+ # Running on real vehicle
+ if self.onboard:
+ # Get all current detected cones
+ cones = []
+ n = 0
+ for id, agent in agents.items():
+ if agent.type == AgentEnum.CONE:
+ # ===== RUNNING ONBOARD =====
+ # cones.append({
+ # 'id': id,
+ # 'x': agent.pose.x,
+ # 'y': agent.pose.y,
+ # 'orientation': agent.activity
+ # })
+ # ===== TESTING ONBOARD in BASIC SIM =====
+ if n % 2 == 0:
+ curr_activity = 'LEFT'
+ elif n % 2 == 1:
+ curr_activity = 'RIGHT'
+ else:
+ curr_activity = 'STANDING'
+ cones.append({
+ 'id': id,
+ 'x': agent.pose.x,
+ 'y': agent.pose.y,
+ 'orientation': curr_activity
+ })
+ n = n + 1
+
+ vehicle_dict = {
+ 'position': [vehicle.pose.x, vehicle.pose.y],
+ 'heading': vehicle.pose.yaw,
+ 'velocity': vehicle.v
+ }
+ if self.DEBUG_MODE:
+ print("===================== STATES =====================")
+ print(f"Vehicle State: {vehicle_dict}")
+ print(f"Detected Cones: {cones}")
+ print("===================== ====== =====================")
+ # If no cones detected, drive forward
+ if len(cones) == 0:
+ self.trajectory = no_cone_planning(vehicle_dict)
+ # Otherwise, plan trajectory
+ elif got_new_cone(cones, self.prev_cones):
+ # Replan only if new cones are detected
+ self.trajectory = plan_full_slalom_trajectory(vehicle_dict, cones)
+ self.prev_cones = cones
+ else:
+ # No need to update the plan if the same cones are detected
+ self.prev_cones = cones
+
+ # Testing with predefined fake generated cone positions
+ elif self.run_fake_plan:
+ # Example Test - Slalom
+ cones = [
+ {'x': 10, 'y': 0.0, 'orientation': 'LEFT'},
+ {'x': 30, 'y': 1.0, 'orientation': 'RIGHT'},
+ {'x': 50, 'y': 0.0, 'orientation': 'LEFT'},
+ {'x': 70, 'y': 1.0, 'orientation': 'STANDING'},
+ {'x': 50, 'y': 0.0, 'orientation': 'RIGHT'},
+ {'x': 30, 'y': 1.0, 'orientation': 'LEFT'},
+ {'x': 10, 'y': 0.0, 'orientation': 'RIGHT'}
+ ]
+ vehicle_dict = {
+ 'position': [vehicle.pose.x, vehicle.pose.y],
+ 'heading': vehicle.pose.yaw,
+ 'velocity': vehicle.v
+ }
+
+ # Example Test - Racing Circle
+ # cones = [
+ # {'x': -60.083, 'y': -33.118, 'orientation': '90turn'},
+ # {'x': -6.392, 'y': -5.147, 'orientation': '90turn'},
+ # {'x': -5.625, 'y': -13.637, 'orientation': '90turn'},
+ # {'x': -56.258, 'y': -41.080, 'orientation': '90turn'}
+ # ]
+ # vehicle_dict = {
+ # 'position': [-60.0, -39.0],
+ # 'heading': np.pi * 2 / 3,
+ # 'velocity': 0.0
+ # }
+
+ # Example Test - Racing Circle
+ # cones = [
+ # {'x': 0.0, 'y': 70.0, 'orientation': '90turn'},
+ # {'x': 30.0, 'y': 70.0, 'orientation': '90turn'},
+ # {'x': 30.0, 'y': 0.0, 'orientation': '90turn'},
+ # {'x': 0.0, 'y': 0.0, 'orientation': '90turn'}
+ # ]
+ # vehicle_dict = {
+ # 'position': [0.0, 20.0],
+ # 'heading': 0.0,
+ # 'velocity': 0.0
+ # }
+
+ self.trajectory = plan_full_slalom_trajectory(vehicle_dict, cones)
+ self.run_fake_plan = False
+
+ # Update output
+ return self.trajectory
+
+
+
+
+
+
+
+
+
+########################################################################################################################
+########################################################################################################################
+
+# ------------ Test Code START --------------
+
+# ======= Overall test cases to generate full trajectories with known cone positions =======
+def test_4_cone_slalom():
+ vehicle_state = {
+ 'position': [0.0, 0.0],
+ 'heading': 0.0,
+ 'velocity': 5.0
+ }
+
+ cones = [
+ {'x': 10, 'y': 0.0, 'orientation': 'left'},
+ {'x': 30, 'y': 1.0, 'orientation': 'right'},
+ {'x': 50, 'y': 0.0, 'orientation': 'left'},
+ {'x': 70, 'y': 1.0, 'orientation': 'standing'}
+ ]
+
+ flex_wps, fixed_wps = waypoint_search_optimization(vehicle_state, cones, search_attempts=1)
+
+ current_pos = np.array(vehicle_state['position'])
+
+ x_all, y_all = [], []
+
+ for idx, (flex_wp, fixed_wp) in enumerate(zip(flex_wps, fixed_wps)):
+ init_state = {
+ 'x': current_pos[0], 'y': current_pos[1], 'psi': vehicle_state['heading'],
+ 'c': 0.0, 'v': vehicle_state['velocity']
+ }
+ final_state = {
+ 'x': fixed_wp[0], 'y': fixed_wp[1], 'psi': vehicle_state['heading'], 'c': 0.0
+ }
+ x, y, psi, c, v, eps, final_error = trajectory_generation(init_state, final_state, waypoint=flex_wp)
+
+ print(f"\nSegment {idx + 1}:")
+ print(f" Waypoint: {flex_wp}")
+ print(f" Final Errors:")
+ for k, e in final_error.items():
+ print(f" {k}: {e:.4f}")
+
+ x_all += list(x)
+ y_all += list(y)
+
+ plot_trajectory(x, y, v, c, eps, waypoint=flex_wp)
+
+ current_pos = np.array(fixed_wp)
+
+ # Plot overall trajectory
+ plt.figure()
+ plt.plot(x_all, y_all, label='Overall Trajectory')
+
+ # Plot cones
+ for i, cone in enumerate(cones):
+ plt.scatter(cone['x'], cone['y'], color='orange', s=80, label='Cone' if i == 0 else "")
+ plt.text(cone['x'], cone['y'] + 0.5, f'C{i+1}', ha='center', fontsize=9, color='darkorange')
+
+ plt.title('4-Cone Full Course Trajectory')
+ plt.xlabel('X')
+ plt.ylabel('Y')
+ plt.legend()
+ plt.axis('equal')
+ plt.grid(True)
+ plt.show()
+
+########################
+if __name__ == "__main__":
+ def plot_trajectory(x, y, v, c, eps, waypoint=None):
+ plt.figure(figsize=(12, 10))
+
+ # Trajectory plot
+ plt.subplot(4, 1, 1)
+ plt.plot(x, y, label="Trajectory")
+ plt.scatter([x[0], x[-1]], [y[0], y[-1]], color='red', label="Start/End")
+
+ if waypoint is not None:
+ plt.scatter(*waypoint, color='purple', s=60, marker='X', label="Waypoint")
+ plt.annotate("Waypoint", (waypoint[0], waypoint[1]), textcoords="offset points", xytext=(5,5), color='purple')
+
+ plt.axis('equal')
+ plt.ylabel("y (m)")
+ plt.title("Trajectory")
+ plt.grid(True)
+ plt.legend()
+
+ # Speed plot
+ plt.subplot(4, 1, 2)
+ plt.plot(v, label="Speed (v)", color="blue")
+ plt.ylabel("Speed (m/s)")
+ plt.grid(True)
+ plt.legend()
+
+ # Curvature plot
+ plt.subplot(4, 1, 3)
+ plt.plot(c, label="Curvature (c)", color="orange")
+ plt.ylabel("Curvature (1/m)")
+ plt.grid(True)
+ plt.legend()
+
+ # Curvature rate plot
+ plt.subplot(4, 1, 4)
+ plt.plot(eps, label="Curvature Rate (ε)", color="green")
+ plt.xlabel("Step")
+ plt.ylabel("ε (1/m²)")
+ plt.grid(True)
+ plt.legend()
+
+ plt.tight_layout()
+ plt.show()
+
+ # --- Test Case 1: pass a cone in slalom ---
+ def trajectory_generation_test1():
+ # Init and final
+ init_state = {'x': 0.0, 'y': 0.0, 'psi': 0.0, 'c': 0.0, 'v': 5.0}
+ final_state = {'x': 15.0, 'y': 0.0, 'psi': np.pi / 20000000, 'c': np.pi / 20000000}
+ waypoint = (8.0, 6.0)
+
+ # Solve
+ x, y, psi, c, v, eps, final_error = trajectory_generation(
+ init_state, final_state, waypoint=waypoint
+ )
+ plot_trajectory(x, y, v, c, eps, waypoint)
+
+ # Error
+ print("\nFinal State Errors:")
+ for k, e in final_error.items():
+ print(f"{k}: {e:.6f}")
+
+ # --- Test case 2: 90 degree turn ---
+ def trajectory_generation_test2():
+ # Init and final
+ init_state = {'x': 0.0, 'y': 0.0, 'psi': 0.0, 'c': 0.0, 'v': 5.0}
+ final_state = {'x': 15.0, 'y': 15.0, 'psi': np.pi / 2, 'c': np.pi / 2}
+ waypoint = (13.0, 3.0)
+
+ # Solve
+ x, y, psi, c, v, eps, final_error = trajectory_generation(
+ init_state, final_state, waypoint=waypoint
+ )
+ plot_trajectory(x, y, v, c, eps, waypoint)
+
+ # Error
+ print("\nFinal State Errors:")
+ for k, e in final_error.items():
+ print(f"{k}: {e:.6f}")
+
+ #############
+ #########################
+ # --- Test Case ---
+ def test_feasibility_check():
+ N = 50
+ y_traj = np.linspace(0, 10, N)
+ psi_traj = np.linspace(0, 0.1, N)
+ c_traj = np.linspace(0, 0.2, N)
+ trajectory = list(zip(y_traj, psi_traj, c_traj))
+
+ # Cone map near the path
+ cone_map = [(5.0, 1.0), (10.0, 1.5), (15.0, 2.0), (25.0, 4.0), (25.0, 10.0), (16.0, 9.0), (40.0, 5.0)]
+
+ # Run check
+ feasible, collisions, x_vals, y_vals = feasibility_check(trajectory, cone_map)
+
+ # Plot
+ plt.figure(figsize=(10, 6))
+ plt.plot(x_vals, y_vals, label="Trajectory", linewidth=2)
+ for i, (cx, cy) in enumerate(cone_map):
+ color = 'red' if i in collisions else 'green'
+ plt.scatter(cx, cy, color=color, s=100, label=f'Cone {i}' if i == 0 else "")
+ plt.xlabel("x (m)")
+ plt.ylabel("y (m)")
+ plt.title("Trajectory and Cone Map")
+ plt.legend()
+ plt.axis("equal")
+ plt.grid(True)
+ plt.show()
+
+ print("Feasible:", feasible)
+ print("Collisions with cones:", collisions)
+
+
+# TODO 1: Compute target heading in waypoint_generation for different settings (slalom or course run)
+# TODO 2: Implement replanning
+def test_fixed_course():
+ # steering angle c is relative to car heading!!
+ vehicle_state = {
+ 'position': [-60.0, -39.0],
+ 'heading': np.pi * 2 / 3,
+ 'velocity': 0.0
+ }
+
+ cones = [
+ {'x': -60.083, 'y': -33.118, 'orientation': '90turn'},
+ {'x': -6.392, 'y': -5.147, 'orientation': '90turn'},
+ {'x': -5.625, 'y': -13.637, 'orientation': '90turn'},
+ {'x': -56.258, 'y': -41.080, 'orientation': '90turn'}
+ ]
+
+ current_pos = np.array(vehicle_state['position'])
+ current_heading = vehicle_state['heading']
+ current_steering = 0.0
+
+ x_all, y_all = [], []
+
+ for cone_idx, cone in enumerate(cones):
+ print("current cone: ", cone)
+ scenario, flex_wps, fixed_wp = waypoint_generate(vehicle_state, [cone])
+ if not flex_wps or fixed_wp is None:
+ continue
+
+ # Setting target_heading in final_state
+ if cone_idx > 0:
+ prev_cone_position = np.array((cones[cone_idx - 1]['x'], cones[cone_idx - 1]['y']))
+ current_cone_position = np.array((cones[cone_idx]['x'], cones[cone_idx]['y']))
+ target_heading = np.arctan2(current_cone_position[1] - prev_cone_position[1],
+ current_cone_position[0] - prev_cone_position[0]) - np.pi / 2 + np.pi / 18
+
+ else: # no previous cone
+ target_heading = current_heading - np.pi / 2 + np.pi / 18
+
+ # mod to -pi to pi range
+ target_heading = (target_heading + np.pi) % (2 * np.pi) - np.pi
+ current_heading = (current_heading + np.pi) % (2 * np.pi) - np.pi
+
+ if abs(target_heading - current_heading) > np.pi:
+ if target_heading < current_heading:
+ target_heading += 2 * np.pi
+ else:
+ target_heading -= 2 * np.pi
+
+ init_state = {
+ 'x': current_pos[0], 'y': current_pos[1], 'psi': current_heading,
+ 'c': current_steering, 'v': vehicle_state['velocity']
+ }
+
+ final_state = {
+ 'x': fixed_wp[0], 'y': fixed_wp[1], 'psi': target_heading, 'c': 0.0
+ }
+
+ estimated_N = int(((current_pos[0]-fixed_wp[0]) ** 2 + (current_pos[1]-fixed_wp[1]) ** 2) ** 0.5 / 0.7)
+
+ x, y, psi, c, v, eps, _ = trajectory_generation(init_state, final_state, waypoints=flex_wps, N=estimated_N)
+ x_all.extend(x)
+ y_all.extend(y)
+
+ plot_trajectory(x, y, v, c, eps)
+
+ current_pos = np.array([x[-1], y[-1]])
+ current_heading = psi[-1]
+ current_steering = c[-1]
+
+ vehicle_state = {
+ 'position': current_pos,
+ 'heading': current_heading,
+ 'velocity': v[-1]
+ }
+
+ # Plot overall trajectory
+ plt.figure()
+ plt.plot(x_all, y_all, label='Overall Trajectory')
+
+ # Plot cones
+ for i, cone in enumerate(cones):
+ plt.scatter(cone['x'], cone['y'], color='orange', s=10, label='Cone' if i == 0 else "")
+ plt.text(cone['x'], cone['y'] + 0.5, f'C{i+1}', ha='center', fontsize=9, color='darkorange')
+
+ plt.title('4-Cone Full Course Trajectory')
+ plt.xlabel('X')
+ plt.ylabel('Y')
+ plt.legend()
+ plt.axis('equal')
+ plt.grid(True)
+ plt.show()
+
+if __name__ == "__main__":
+ # --------------------------
+ # Plotting Function
+ # --------------------------
+ def plot_results(vehicle_state, cones, wpt_flexes=None, wpt_fixed=None, scenario_label=""):
+ plt.figure(figsize=(10, 5))
+ ax = plt.gca()
+ ax.set_aspect('equal')
+
+ all_x = [cone['x'] for cone in cones] + [vehicle_state['position'][0]]
+ all_y = [cone['y'] for cone in cones] + [vehicle_state['position'][1]]
+
+ if wpt_flexes is not None:
+ all_x += [pt[0] for pt in wpt_flexes]
+ all_y += [pt[1] for pt in wpt_flexes]
+
+ if wpt_fixed is not None:
+ all_x.append(wpt_fixed[0])
+ all_y.append(wpt_fixed[1])
+
+ # Compute axis limits with padding
+ padding = 2
+ x_min, x_max = min(all_x) - padding, max(all_x) + padding
+ y_min, y_max = min(all_y) - padding, max(all_y) + padding
+ plt.xlim(x_min, x_max)
+ plt.ylim(y_min, y_max)
+
+ # Plot cones
+ for cone in cones:
+ plt.scatter(cone['x'], cone['y'], c='orange', label='Cone' if cone == cones[0] else "")
+ plt.text(cone['x'], cone['y'] + 0.5, cone['orientation'][0].upper(), fontsize=10, ha='center')
+
+ # Plot vehicle
+ vx, vy = vehicle_state['position']
+ plt.plot(vx, vy, 'bo', label='Vehicle Start')
+ plt.arrow(vx, vy, np.cos(vehicle_state['heading']) * 2, np.sin(vehicle_state['heading']) * 2,
+ head_width=0.25, color='blue')
+
+ # Plot flexible waypoint
+ if wpt_flexes is not None:
+ for wpt_flex in wpt_flexes:
+ plt.plot(wpt_flex[0], wpt_flex[1], 'go', label='Flexible Waypoint')
+ plt.text(wpt_flex[0], wpt_flex[1] + 0.5, 'Flex', fontsize=9, color='green')
+
+ # Plot fixed waypoint
+ if wpt_fixed is not None:
+ plt.plot(wpt_fixed[0], wpt_fixed[1], 'ro', label='Fixed Waypoint')
+ plt.text(wpt_fixed[0], wpt_fixed[1] + 0.5, 'Fixed', fontsize=9, color='red')
+
+ plt.title(scenario_label)
+ plt.xlabel("X")
+ plt.ylabel("Y")
+ plt.grid(True)
+ plt.legend()
+ plt.show()
+ return
+
+ # --------------------------
+ # Vehicle State Test Update
+ # --------------------------
+ def drive(vehicle_state):
+ # Update vehicle state
+ vehicle_state['position'][0] += vehicle_state['velocity'] * np.cos(vehicle_state['heading'])
+ vehicle_state['position'][1] += vehicle_state['velocity'] * np.sin(vehicle_state['heading'])
+ return vehicle_state
+ # --------------------------
+ # Step 1: Generate Fake Cones
+ # --------------------------
+ def generate_test_cones(case='slalom'):
+ if case == 'slalom':
+ cones = []
+ for i in range(3):
+ x = (i+1) * 10
+ y = 0 if i % 2 == 0 else 1
+ orientation = 'left' if i % 2 == 0 else 'right'
+ cones.append({'x': x, 'y': y, 'orientation': orientation})
+ return cones
+
+ elif case == 'u_turn':
+ return [{'x': 10, 'y': 0, 'orientation': 'standing'}]
+
+ # --------------------------
+ # Step 2: Define Fake Vehicle
+ # --------------------------
+ def get_test_vehicle_state(vehicle_state=None):
+ if vehicle_state is not None:
+ return vehicle_state
+ return {
+ 'position': [0, 0],
+ 'heading': 0.0 * 180/np.pi, # Facing right
+ 'velocity': 10.0
+ }
+
+ # --------------------------
+ # Step 3: Run Scenario + Waypoints
+ # --------------------------
+ def test_waypoint_generation(case='slalom', test_loop=1):
+ vehicle_state = get_test_vehicle_state()
+ cones = generate_test_cones(case)
+
+ for i in range(test_loop):
+ scenario = scenario_check(vehicle_state, cones)
+ scenario_label = f"Scenario: {scenario}"
+ scenario, wpt_flexes, wpt_fixed = waypoint_generate(vehicle_state, cones)
+ plot_results(vehicle_state, cones, wpt_flexes, wpt_fixed, scenario_label)
+ vehicle_state = drive(vehicle_state)
+ if case == 'slalom':
+ cones.pop(0)
+
+ # --------------------------
+ # Main for waypoint
+ # --------------------------
+ # test_waypoint_generation(case='slalom', test_loop=2)
+ # test_waypoint_generation(case='u_turn')
+
+
+ # --------------------------
+ ### Combine Test
+ # --------------------------
+ def test_planning(case='slalom', test_loop=2):
+ vehicle_state = get_test_vehicle_state()
+ cones = generate_test_cones(case)
+
+ for i in range(test_loop):
+ # Way Points
+ scenario = scenario_check(vehicle_state, cones)
+ scenario_label = f"Scenario: {scenario}"
+ scenario, wpt_flexes, wpt_fixed = waypoint_generate(vehicle_state, cones)
+ plot_results(vehicle_state, cones, wpt_flexes, wpt_fixed, scenario_label)
+ # Trajectory
+ init_state = {'y': wpt_flexes[0][1], 'psi': 0.0, 'c': 0.0}
+ final_state = {'y': wpt_fixed[1], 'psi': 0.0, 'c': 0.0}
+
+ y_traj, psi_traj, c_traj, eps_traj = trajectory_generation(init_state, final_state)
+ # plot_trajectory(y_traj, psi_traj, c_traj, label="Generated trajectory")
+ # plot_dynamics(psi_traj, c_traj, eps_traj)
+
+ # Iterate
+ vehicle_state = drive(vehicle_state)
+ if case == 'slalom':
+ cones.pop(0)
+ # test_planning(case='slalom', test_loop=2)
+# ------------ Test Code END --------------
\ No newline at end of file
diff --git a/GEMstack/onboard/planning/racing_planning_old.py b/GEMstack/onboard/planning/racing_planning_old.py
new file mode 100644
index 000000000..54085a656
--- /dev/null
+++ b/GEMstack/onboard/planning/racing_planning_old.py
@@ -0,0 +1,840 @@
+from ...state.trajectory import Trajectory
+from ...state.vehicle import VehicleState
+from ..component import Component
+
+from ...state.trajectory import Trajectory, compute_headings, Path#, racing_velocity_profile
+from ...state.physical_object import ObjectFrameEnum
+
+import numpy as np
+import matplotlib.pyplot as plt
+from scipy.optimize import minimize
+
+
+
+# --------------------------------------------------------------------------- Hua-Ta's Code START
+def scenario_check(vehicle_state, cone_state):
+ """
+ Check the cone state and determine the scenario.
+ Args:
+ vehicle_state: The state of the vehicle.
+ cone_state: The state of the cones.
+ Returns:
+ str: The scenario type.
+ - 'left_pass': cone pointed left, go left
+ - 'right_pass': cone pointed right, go right
+ - 'u_turn': cone standing up, make a U-turn
+ tuple: (cone_x, cone__y)
+ """
+ # Get the closest cone info
+ cones_ahead = sorted(cone_state, key=lambda c: np.linalg.norm(
+ np.array([c['x'], c['y']]) - np.array(vehicle_state['position'])))
+ cone_direction = cones_ahead[0]['orientation']
+ cone_position = (cones_ahead[0]['x'], cones_ahead[0]['y'])
+
+ # Check the cone orientation
+ if cone_direction != 'left' and cone_direction != 'right' and cone_direction != 'standing':
+ raise ValueError("Unknown cone orientation")
+
+ return cone_direction, cone_position
+
+def waypoint_generate(vehicle_state, cone_state):
+ """
+ Generate waypoints based on the scenario.
+ Args:
+ vehicle_state: The state of the vehicle.
+ cone_state: The state of the cones.
+ Returns:
+ Tuple[str, Tuple[float, float], Tuple[float, float]]:
+ scenario: detected scenario type
+ flex_wp: flexible waypoint (used to maneuver)
+ fixed_wp: fixed waypoint (goal position)
+ """
+ scenario, cone_position = scenario_check(vehicle_state, cone_state)
+ car_position = np.array(vehicle_state['position'])
+ car_heading = vehicle_state['heading'] # in radians
+
+ # ===== Parameters =====
+ u_turn_radius = 5.0 # Radius for U-turn
+ offset = 2.0 # Offset for left/right pass
+ lookahead_distance = 10.0 # Distance ahead for fixed point
+ # ======================
+
+ # Direction vector based on heading
+ heading_vector = np.array([np.cos(car_heading), np.sin(car_heading)])
+
+ # Vector perpendicular to heading (to determine left/right)
+ perpendicular_vector = np.array([-np.sin(car_heading), np.cos(car_heading)])
+
+ if scenario == 'standing':
+ # U-turn: Generate points in a semi-circular arc around the cone
+ cone = np.array(cone_position)
+
+ # Number of waypoints to generate for the arc
+ num_arc_points = 7
+
+ # Generate waypoints in a smooth semi-circular pattern on the RIGHT side
+ flex_wps_list = []
+
+ # Create a semi-circular arc from 0 to π
+ # But negate perpendicular_vector to go to the right side
+ for i in range(num_arc_points):
+ # Calculate angle in the semi-circle (0 to π)
+ angle = i * np.pi / (num_arc_points - 1)
+
+ # MODIFIED: Negative perpendicular_vector to go to right side of cone
+ # This creates a counter-clockwise turn around the cone
+ wp = cone - u_turn_radius * (
+ perpendicular_vector * np.cos(angle) -
+ heading_vector * np.sin(angle)
+ )
+
+ flex_wps_list.append(wp)
+
+ # Fixed waypoint: behind the cone after U-turn (also on right side)
+ fixed_wp = cone + u_turn_radius * perpendicular_vector
+
+ # For visualization only
+ # for i, wp in enumerate(flex_wps_list):
+ # plt.plot(wp[0], wp[1], 'ro') # Plot all waypoints in red
+ # plt.text(wp[0], wp[1], f'wp{i}', fontsize=9)
+
+ # plt.plot(fixed_wp[0], fixed_wp[1], 'bo') # Plot fixed waypoint in blue
+ # plt.plot(cone[0], cone[1], 'gx') # Plot cone in green
+ # plt.plot(car_position[0], car_position[1], 'ks') # Plot car position
+ # plt.axis('equal') # Equal aspect ratio for better visualization
+ # plt.grid(True)
+ # plt.show()
+
+ elif scenario == 'left':
+ cone = np.array(cone_position)
+
+ # Flexible waypoint: go to the left of the cone
+ flex_wp1 = cone + offset * perpendicular_vector
+ flex_wps_list = [flex_wp1]
+
+ # Fixed waypoint: forward after passing the cone
+ # fixed_wp = flex_wp + heading_vector * lookahead_distance - offset * perpendicular_vector * 2
+ fixed_wp = flex_wp1 + heading_vector * lookahead_distance - offset * perpendicular_vector
+
+ elif scenario == 'right':
+ cone = np.array(cone_position)
+
+ # Flexible waypoint: go to the right of the cone
+ flex_wp1 = cone - offset * perpendicular_vector
+ flex_wps_list = [flex_wp1]
+
+ # Fixed waypoint: forward after passing the cone
+ # fixed_wp = flex_wp + heading_vector * lookahead_distance + offset * perpendicular_vector * 2
+ fixed_wp = flex_wp1 + heading_vector * lookahead_distance + offset * perpendicular_vector
+
+ else:
+ flex_wps_list = None
+ fixed_wp = None
+
+ return scenario, flex_wps_list, fixed_wp
+
+def velocity_profiling(path, acceleration, deceleration, max_speed, current_speed, lateral_acc_limit):
+ """
+ Returns a trajectory with velocity profile that respects:
+ 1. max longitudinal acceleration
+ 2. max deceleration
+ 3. max lateral acceleration from curvature
+ 4. max speed
+ """
+ # Curvature-based speed limit
+ curvature_safe_speeds = []
+ for p in path.curvature:
+ if abs(p) < 1e-3:
+ curvature_safe_speeds.append(max_speed)
+ else:
+ max_v = np.sqrt(lateral_acc_limit / abs(p))
+ curvature_safe_speeds.append(min(max_v, max_speed))
+
+ # Create a custom profile-aware speed function
+ def dynamic_max_speed_at(index):
+ return curvature_safe_speeds[min(index, len(curvature_safe_speeds) - 1)]
+
+ # You can inject dynamic speed limit into your plan
+ return
+# --------------------------------------------------------------------------- Hua-Ta's Code END
+
+# --------------------------------------------------------------------------- Shilan's Code START
+# ORIGINAL CODE
+# def trajectory_generation(init_state, final_state, N=30, T=0.1, Lr=1.5,
+# w_c=10.0, w_eps=0.0, w_vvar=5.0,
+# w_terminal=10.0,
+# v_min=3.0, v_max=11.0,
+# waypoint=None, waypoint_penalty_weight=100.0):
+# """
+# Generate a dynamically feasible trajectory between init_state and final_state (optionally pass a (x,y) waypoint)
+# using curvature-based vehicle dynamics and nonlinear optimization.
+
+# Note: We minimize variance of velocity to roughly keep constant velocity so it does not affect the turning radius.
+
+# Thoughts: The trajectory generated from large velocity and large curvature rate can be similar to the trajectory
+# generated using small velovity and small curvature rate, might be scaled versions if the proportions are proper.
+# For racing, we want to use the maximum velocity. So maybe we should scale the trajectory using the allowed velocity??? (TODO)
+# And how to obtain that??? (TODO)
+
+# TODO: remove v in init_state
+
+# Parameters:
+# - init_state (dict): Initial vehicle state with keys 'x', 'y', 'psi', 'c', 'v'.
+# - final_state (dict): Target vehicle state with keys 'x', 'y', 'psi', 'c'.
+# - N (int): Number of discrete time steps in the trajectory.
+# - T (float): Duration of each time step (in seconds).
+# - Lr (float): Distance from the vehicle's center to the rear axle. # TODO: find this value for GEMe4
+# - w_c (float): Weight for penalizing curvature (smoothness of turns).
+# - w_eps (float): Weight for penalizing curvature rate (reduces sharp steering changes).
+# - w_vvar (float): Weight for penalizing speed variance (encourages speed smoothness).
+# - w_terminal (float): Weight for penalizing final state deviation (soft constraint).
+# - v_min (float): Minimum allowed speed (in m/s).
+# - v_max (float): Maximum allowed speed (in m/s).
+# - waypoint (tuple or None): Optional (x, y) coordinate that the trajectory should pass near.
+# - waypoint_penalty_weight (float): Penalty weight for distance from waypoint (soft constraint).
+
+# Returns:
+# - x, y, psi, c, v, eps (np.ndarray): Arrays of optimized state and control values.
+# - final_error (dict): Final state errors in x, y, psi, and c.
+# """
+# def cost(p):
+# x_, y_, psi_, c_, v_, eps_ = np.split(p, [N - 1, 2 * (N - 1), 3 * (N - 1), 4 * (N - 1), 5 * (N - 1)])
+# c_seq = np.concatenate(([init_state['c']], c_))
+# v_seq = np.concatenate(([init_state['v']], v_))
+# x_final, y_final, psi_final, c_final = x_[-1], y_[-1], psi_[-1], c_[-1]
+
+# cost_c = w_c * np.sum(c_seq ** 2)
+# cost_eps = w_eps * np.sum(eps_ ** 2)
+# v_mean = np.mean(v_seq)
+# cost_vvar = w_vvar * np.mean((v_seq - v_mean) ** 2)
+
+# cost_terminal = w_terminal * (
+# (x_final - final_state['x']) ** 2 +
+# (y_final - final_state['y']) ** 2 +
+# (psi_final - final_state['psi']) ** 2 * 100 +
+# (c_final - final_state['c']) ** 2 * 100 # TODO: remove magic constant
+# )
+
+# cost_waypoint = 0.0
+# if waypoint is not None:
+# # use midpoint index to check passing near the waypoint
+# mid = N // 2
+# cost_waypoint = waypoint_penalty_weight * (
+# (x_[mid-1] - waypoint[0])**2 + (y_[mid-1] - waypoint[1])**2
+# )
+
+# return cost_c + cost_eps + cost_vvar + cost_terminal + cost_waypoint
+
+# def dynamics_constraints(p):
+# x_, y_, psi_, c_, v_, eps_ = np.split(p, [N - 1, 2 * (N - 1), 3 * (N - 1), 4 * (N - 1), 5 * (N - 1)])
+# constraints = []
+# x_prev, y_prev, psi_prev, c_prev, v_prev = init_state['x'], init_state['y'], init_state['psi'], init_state['c'], init_state['v']
+# for k in range(N - 1):
+# dx = v_prev * np.cos(psi_prev + c_prev * Lr) * T
+# dy = v_prev * np.sin(psi_prev + c_prev * Lr) * T
+# dpsi = v_prev * c_prev * T
+# dc = eps_[k] * T
+# constraints.extend([
+# x_[k] - (x_prev + dx),
+# y_[k] - (y_prev + dy),
+# psi_[k] - (psi_prev + dpsi),
+# c_[k] - (c_prev + dc)
+# ])
+# x_prev, y_prev, psi_prev, c_prev, v_prev = x_[k], y_[k], psi_[k], c_[k], v_[k]
+# return constraints
+
+# # Initial guesses
+# x_vals = np.linspace(init_state['x'], final_state['x'], N)
+# y_vals = np.linspace(init_state['y'], final_state['y'], N)
+# psi_vals = np.linspace(init_state['psi'], final_state['psi'], N)
+# c_vals = np.linspace(init_state['c'], final_state['c'], N)
+# v_vals = np.ones(N) * init_state['v']
+# eps_vals = np.zeros(N - 1)
+
+# p0 = np.concatenate([x_vals[1:], y_vals[1:], psi_vals[1:], c_vals[1:], v_vals[1:], eps_vals])
+# bounds = [(None, None)] * (4 * (N - 1)) + [(v_min, v_max)] * (N - 1) + [(None, None)] * (N - 1)
+
+# result = minimize(cost, p0, bounds=bounds,
+# constraints={'type': 'eq', 'fun': dynamics_constraints},
+# options={'maxiter': 1000})
+# if not result.success:
+# raise RuntimeError("Optimization failed")
+
+# x_, y_, psi_, c_, v_, eps_ = np.split(result.x, [N - 1, 2 * (N - 1), 3 * (N - 1), 4 * (N - 1), 5 * (N - 1)])
+# x_full = np.concatenate(([init_state['x']], x_))
+# y_full = np.concatenate(([init_state['y']], y_))
+# psi_full = np.concatenate(([init_state['psi']], psi_))
+# c_full = np.concatenate(([init_state['c']], c_))
+# v_full = np.concatenate(([init_state['v']], v_))
+
+# final_error = {
+# 'x_error': abs(x_full[-1] - final_state['x']),
+# 'y_error': abs(y_full[-1] - final_state['y']),
+# 'psi_error': abs(psi_full[-1] - final_state['psi']),
+# 'c_error': abs(c_full[-1] - final_state['c']),
+# }
+
+# return x_full, y_full, psi_full, c_full, v_full, eps_, final_error
+def trajectory_generation(init_state, final_state, N=30, T=0.1, Lr=1.5,
+ w_c=10.0, w_eps=0.0, w_vvar=5.0,
+ w_terminal=10.0,
+ v_min=3.0, v_max=11.0,
+ waypoints=None, waypoint_penalty_weight=100.0):
+ """
+ Generate a dynamically feasible trajectory between init_state and final_state
+ using curvature-based vehicle dynamics and nonlinear optimization.
+
+ Now supports multiple waypoints.
+
+ Parameters:
+ - init_state (dict): Initial vehicle state with keys 'x', 'y', 'psi', 'c', 'v'.
+ - final_state (dict): Target vehicle state with keys 'x', 'y', 'psi', 'c'.
+ - N (int): Number of discrete time steps in the trajectory.
+ - T (float): Duration of each time step (in seconds).
+ - Lr (float): Distance from the vehicle's center to the rear axle.
+ - w_c (float): Weight for penalizing curvature (smoothness of turns).
+ - w_eps (float): Weight for penalizing curvature rate (reduces sharp steering changes).
+ - w_vvar (float): Weight for penalizing speed variance (encourages speed smoothness).
+ - w_terminal (float): Weight for penalizing final state deviation (soft constraint).
+ - v_min (float): Minimum allowed speed (in m/s).
+ - v_max (float): Maximum allowed speed (in m/s).
+ - waypoints (list or None): Optional list of (x, y) coordinates that the trajectory should pass near.
+ - waypoint_penalty_weight (float): Penalty weight for distance from waypoints (soft constraint).
+
+ Returns:
+ - x, y, psi, c, v, eps (np.ndarray): Arrays of optimized state and control values.
+ - final_error (dict): Final state errors in x, y, psi, and c.
+ """
+ def cost(p):
+ x_, y_, psi_, c_, v_, eps_ = np.split(p, [N - 1, 2 * (N - 1), 3 * (N - 1), 4 * (N - 1), 5 * (N - 1)])
+ c_seq = np.concatenate(([init_state['c']], c_))
+ v_seq = np.concatenate(([init_state['v']], v_))
+ x_final, y_final, psi_final, c_final = x_[-1], y_[-1], psi_[-1], c_[-1]
+
+ cost_c = w_c * np.sum(c_seq ** 2)
+ cost_eps = w_eps * np.sum(eps_ ** 2)
+ v_mean = np.mean(v_seq)
+ cost_vvar = w_vvar * np.mean((v_seq - v_mean) ** 2)
+
+ cost_terminal = w_terminal * (
+ (x_final - final_state['x']) ** 2 +
+ (y_final - final_state['y']) ** 2 +
+ (psi_final - final_state['psi']) ** 2 * 100 +
+ (c_final - final_state['c']) ** 2 * 100
+ )
+
+ cost_waypoints = 0.0
+ if waypoints is not None and len(waypoints) > 0:
+ # Calculate equally spaced indices for each waypoint
+ num_waypoints = len(waypoints)
+ indices = [int((i + 1) * (N - 1) / (num_waypoints + 1)) for i in range(num_waypoints)]
+
+ # Sum penalties for each waypoint at its corresponding index
+ for wp_idx, waypoint in enumerate(waypoints):
+ traj_idx = indices[wp_idx]
+ cost_waypoints += waypoint_penalty_weight * (
+ (x_[traj_idx] - waypoint[0])**2 + (y_[traj_idx] - waypoint[1])**2
+ )
+
+ return cost_c + cost_eps + cost_vvar + cost_terminal + cost_waypoints
+ def dynamics_constraints(p):
+ x_, y_, psi_, c_, v_, eps_ = np.split(p, [N - 1, 2 * (N - 1), 3 * (N - 1), 4 * (N - 1), 5 * (N - 1)])
+ constraints = []
+ x_prev, y_prev, psi_prev, c_prev, v_prev = init_state['x'], init_state['y'], init_state['psi'], init_state['c'], init_state['v']
+ for k in range(N - 1):
+ dx = v_prev * np.cos(psi_prev + c_prev * Lr) * T
+ dy = v_prev * np.sin(psi_prev + c_prev * Lr) * T
+ dpsi = v_prev * c_prev * T
+ dc = eps_[k] * T
+ constraints.extend([
+ x_[k] - (x_prev + dx),
+ y_[k] - (y_prev + dy),
+ psi_[k] - (psi_prev + dpsi),
+ c_[k] - (c_prev + dc)
+ ])
+ x_prev, y_prev, psi_prev, c_prev, v_prev = x_[k], y_[k], psi_[k], c_[k], v_[k]
+ return constraints
+
+ # Initial guesses
+ x_vals = np.linspace(init_state['x'], final_state['x'], N)
+ y_vals = np.linspace(init_state['y'], final_state['y'], N)
+ psi_vals = np.linspace(init_state['psi'], final_state['psi'], N)
+ c_vals = np.linspace(init_state['c'], final_state['c'], N)
+ v_vals = np.ones(N) * init_state['v']
+ eps_vals = np.zeros(N - 1)
+
+ p0 = np.concatenate([x_vals[1:], y_vals[1:], psi_vals[1:], c_vals[1:], v_vals[1:], eps_vals])
+ bounds = [(None, None)] * (4 * (N - 1)) + [(v_min, v_max)] * (N - 1) + [(None, None)] * (N - 1)
+
+ result = minimize(cost, p0, bounds=bounds,
+ constraints={'type': 'eq', 'fun': dynamics_constraints},
+ options={'maxiter': 1000})
+ if not result.success:
+ raise RuntimeError("Optimization failed")
+
+ x_, y_, psi_, c_, v_, eps_ = np.split(result.x, [N - 1, 2 * (N - 1), 3 * (N - 1), 4 * (N - 1), 5 * (N - 1)])
+ x_full = np.concatenate(([init_state['x']], x_))
+ y_full = np.concatenate(([init_state['y']], y_))
+ psi_full = np.concatenate(([init_state['psi']], psi_))
+ c_full = np.concatenate(([init_state['c']], c_))
+ v_full = np.concatenate(([init_state['v']], v_))
+
+ final_error = {
+ 'x_error': abs(x_full[-1] - final_state['x']),
+ 'y_error': abs(y_full[-1] - final_state['y']),
+ 'psi_error': abs(psi_full[-1] - final_state['psi']),
+ 'c_error': abs(c_full[-1] - final_state['c']),
+ }
+
+ return x_full, y_full, psi_full, c_full, v_full, eps_, final_error
+
+def feasibility_check(trajectory, cone_map, car_width=2.0, safety_margin=0.3, v=10.0, Lr=1.5, T=0.1):
+ """
+ Check if the car trajectory collides with any cones.
+
+ Parameters:
+ - trajectory: list of (y, psi, c) states
+ - cone_map: list of (x, y) cone positions
+ - car_width: width of the vehicle in meters
+ - safety_margin: buffer around the vehicle
+ - v: vehicle constant speed (used for x position estimation)
+ - Lr: distance to rear axle
+ - T: time step
+
+ Returns:
+ - feasible: True if no collisions
+ - collisions: list of indices of cones that were collided with (for plotting purpose)
+ - x_vals, y_vals: trajectory positions for plotting (for plotting purpose)
+ """
+ y_vals, psi_vals, c_vals = zip(*trajectory)
+ x_vals = [0.0]
+ for i in range(1, len(trajectory)):
+ dx = v * np.cos(psi_vals[i-1] + c_vals[i-1] * Lr) * T
+ x_vals.append(x_vals[-1] + dx)
+
+ collision_radius = (car_width / 2.0) + safety_margin
+ collisions = []
+
+ for j, (cone_x, cone_y) in enumerate(cone_map):
+ for x, y in zip(x_vals, y_vals):
+ if np.hypot(x - cone_x, y - cone_y) < collision_radius:
+ collisions.append(j)
+ break
+
+ feasible = len(collisions) == 0
+ return feasible, collisions, x_vals, y_vals
+########################
+if __name__ == "__main__":
+ def plot_trajectory(x, y, v, c, eps, waypoint=None):
+ plt.figure(figsize=(12, 10))
+
+ # Trajectory plot
+ plt.subplot(4, 1, 1)
+ plt.plot(x, y, label="Trajectory")
+ plt.scatter([x[0], x[-1]], [y[0], y[-1]], color='red', label="Start/End")
+
+ if waypoint is not None:
+ plt.scatter(*waypoint, color='purple', s=60, marker='X', label="Waypoint")
+ plt.annotate("Waypoint", (waypoint[0], waypoint[1]), textcoords="offset points", xytext=(5,5), color='purple')
+
+ plt.axis('equal')
+ plt.ylabel("y (m)")
+ plt.title("Trajectory")
+ plt.grid(True)
+ plt.legend()
+
+ # Speed plot
+ plt.subplot(4, 1, 2)
+ plt.plot(v, label="Speed (v)", color="blue")
+ plt.ylabel("Speed (m/s)")
+ plt.grid(True)
+ plt.legend()
+
+ # Curvature plot
+ plt.subplot(4, 1, 3)
+ plt.plot(c, label="Curvature (c)", color="orange")
+ plt.ylabel("Curvature (1/m)")
+ plt.grid(True)
+ plt.legend()
+
+ # Curvature rate plot
+ plt.subplot(4, 1, 4)
+ plt.plot(eps, label="Curvature Rate (ε)", color="green")
+ plt.xlabel("Step")
+ plt.ylabel("ε (1/m²)")
+ plt.grid(True)
+ plt.legend()
+
+ plt.tight_layout()
+ plt.show()
+
+ # --- Test Case 1: pass a cone in slalom ---
+ def trajectory_generation_test1():
+ # Init and final
+ init_state = {'x': 0.0, 'y': 0.0, 'psi': 0.0, 'c': 0.0, 'v': 5.0}
+ final_state = {'x': 15.0, 'y': 0.0, 'psi': np.pi / 20000000, 'c': np.pi / 20000000}
+ waypoint = (8.0, 6.0)
+
+ # Solve
+ x, y, psi, c, v, eps, final_error = trajectory_generation(
+ init_state, final_state, waypoint=waypoint
+ )
+ plot_trajectory(x, y, v, c, eps, waypoint)
+
+ # Error
+ print("\nFinal State Errors:")
+ for k, e in final_error.items():
+ print(f"{k}: {e:.6f}")
+
+ # --- Test case 2: 90 degree turn ---
+ def trajectory_generation_test2():
+ # Init and final
+ init_state = {'x': 0.0, 'y': 0.0, 'psi': 0.0, 'c': 0.0, 'v': 5.0}
+ final_state = {'x': 15.0, 'y': 15.0, 'psi': np.pi / 2, 'c': np.pi / 2}
+ waypoint = (13.0, 3.0)
+
+ # Solve
+ x, y, psi, c, v, eps, final_error = trajectory_generation(
+ init_state, final_state, waypoint=waypoint
+ )
+ plot_trajectory(x, y, v, c, eps, waypoint)
+
+ # Error
+ print("\nFinal State Errors:")
+ for k, e in final_error.items():
+ print(f"{k}: {e:.6f}")
+
+ #############
+ #########################
+ # --- Test Case ---
+ def test_feasibility_check():
+ N = 50
+ y_traj = np.linspace(0, 10, N)
+ psi_traj = np.linspace(0, 0.1, N)
+ c_traj = np.linspace(0, 0.2, N)
+ trajectory = list(zip(y_traj, psi_traj, c_traj))
+
+ # Cone map near the path
+ cone_map = [(5.0, 1.0), (10.0, 1.5), (15.0, 2.0), (25.0, 4.0), (25.0, 10.0), (16.0, 9.0), (40.0, 5.0)]
+
+ # Run check
+ feasible, collisions, x_vals, y_vals = feasibility_check(trajectory, cone_map)
+
+ # Plot
+ plt.figure(figsize=(10, 6))
+ plt.plot(x_vals, y_vals, label="Trajectory", linewidth=2)
+ for i, (cx, cy) in enumerate(cone_map):
+ color = 'red' if i in collisions else 'green'
+ plt.scatter(cx, cy, color=color, s=100, label=f'Cone {i}' if i == 0 else "")
+ plt.xlabel("x (m)")
+ plt.ylabel("y (m)")
+ plt.title("Trajectory and Cone Map")
+ plt.legend()
+ plt.axis("equal")
+ plt.grid(True)
+ plt.show()
+
+ print("Feasible:", feasible)
+ print("Collisions with cones:", collisions)
+# --------------------------------------------------------------------------- Shilan's Code END
+
+
+def waypoint_search_optimization(vehicle_state, cones, search_attempts=3):
+ valid_flex_wps = []
+ valid_fixed_wps = []
+ current_state = vehicle_state.copy()
+ cones_copy = cones.copy()
+
+ for i in range(min(search_attempts, len(cones_copy))):
+ scenario, flex_wps, fixed_wp = waypoint_generate(current_state, cones_copy)
+
+ if flex_wps is None or fixed_wp is None:
+ break
+
+ for flex_wp in flex_wps:
+ init_state = {
+ 'x': current_state['position'][0],
+ 'y': current_state['position'][1],
+ 'psi': current_state['heading'],
+ 'c': 0.0,
+ 'v': current_state['velocity']
+ }
+ final_state = {
+ 'x': fixed_wp[0],
+ 'y': fixed_wp[1],
+ 'psi': current_state['heading'],
+ 'c': 0.0
+ }
+
+ try:
+ x, y, psi, c, v, eps, final_error = trajectory_generation(init_state, final_state, waypoint=flex_wp)
+ trajectory = list(zip(y, psi, c))
+ feasible, collisions, x_vals, y_vals = feasibility_check(trajectory, [(cone['x'], cone['y']) for cone in cones])
+ print(f"Checking waypoint: {flex_wp}, Fixed: {fixed_wp}, Feasible: {feasible}, Collisions: {collisions}")
+ if feasible:
+ valid_flex_wps.append(flex_wp)
+ valid_fixed_wps.append(fixed_wp)
+ current_state['position'] = list(fixed_wp)
+ break
+ except:
+ continue
+
+ if len(cones_copy) > 0:
+ cones_copy.pop(0)
+
+ return valid_flex_wps, valid_fixed_wps
+
+
+def test_4_cone_slalom():
+ vehicle_state = {
+ 'position': [0.0, 0.0],
+ 'heading': 0.0,
+ 'velocity': 5.0
+ }
+
+ cones = [
+ {'x': 10, 'y': 0.0, 'orientation': 'left'},
+ {'x': 30, 'y': 1.0, 'orientation': 'right'},
+ {'x': 50, 'y': 0.0, 'orientation': 'left'},
+ {'x': 70, 'y': 1.0, 'orientation': 'standing'}
+ ]
+
+ flex_wps, fixed_wps = waypoint_search_optimization(vehicle_state, cones, search_attempts=4)
+
+ current_pos = np.array(vehicle_state['position'])
+
+ for idx, (flex_wp, fixed_wp) in enumerate(zip(flex_wps, fixed_wps)):
+ init_state = {
+ 'x': current_pos[0], 'y': current_pos[1], 'psi': vehicle_state['heading'],
+ 'c': 0.0, 'v': vehicle_state['velocity']
+ }
+ final_state = {
+ 'x': fixed_wp[0], 'y': fixed_wp[1], 'psi': vehicle_state['heading'], 'c': 0.0
+ }
+ x, y, psi, c, v, eps, final_error = trajectory_generation(init_state, final_state, waypoint=flex_wp)
+
+ print(f"\nSegment {idx + 1}:")
+ print(f" Waypoint: {flex_wp}")
+ print(f" Final Errors:")
+ for k, e in final_error.items():
+ print(f" {k}: {e:.4f}")
+
+ plot_trajectory(x, y, v, c, eps, waypoint=flex_wp)
+
+ current_pos = np.array(fixed_wp)
+
+#test_4_cone_slalom()
+
+def to_gemstack_trajectory(x_all, y_all, v_all, T=0.1):
+ t_vals = np.arange(len(x_all)) * T
+ combined_xy = [[x, y] for x, y in zip(x_all, y_all)]
+ curr_path = Path(ObjectFrameEnum.START,combined_xy)
+ path = compute_headings(curr_path)
+ path_normalized = path.arc_length_parameterize()
+ points = [p for p in path_normalized.points]
+ return Trajectory(points=points, times=t_vals, frame=ObjectFrameEnum.START)
+
+def plan_full_slalom_trajectory(vehicle_state, cones):
+ x_all, y_all, v_all = [], [], []
+ current_pos = np.array(vehicle_state['position'])
+ current_heading = vehicle_state['heading']
+
+ for cone in cones:
+ scenario, flex_wps, fixed_wp = waypoint_generate(vehicle_state, [cone])
+ if not flex_wps or fixed_wp is None:
+ continue
+ # flex_wp = flex_wps[0]
+
+ init_state = {
+ 'x': current_pos[0], 'y': current_pos[1], 'psi': current_heading,
+ 'c': 0.0, 'v': vehicle_state['velocity']
+ }
+ final_state = {
+ 'x': fixed_wp[0], 'y': fixed_wp[1], 'psi': current_heading, 'c': 0.0
+ }
+
+ x, y, psi, c, v, eps, _ = trajectory_generation(init_state, final_state, waypoints=flex_wps)
+ x_all.extend(x)
+ y_all.extend(y)
+ v_all.extend(v)
+
+ current_pos = np.array([x[-1], y[-1]])
+
+ return to_gemstack_trajectory(x_all, y_all, v_all)
+
+# def test_slalom_fixe
+
+class SlalomTrajectoryPlanner(Component):
+ def __init__(self, **kwargs):
+ # You can accept args here if needed
+ self.trajectory = None
+ self.planned = False
+
+ def state_inputs(self):
+ return ['vehicle'] # Will receive a VehicleState input
+
+ def state_outputs(self):
+ return ['trajectory']
+
+ def update(self, vehicle: VehicleState):
+ if not self.planned:
+ cones = [
+ {'x': 10, 'y': 0.0, 'orientation': 'left'},
+ {'x': 30, 'y': 1.0, 'orientation': 'right'},
+ {'x': 50, 'y': 0.0, 'orientation': 'left'},
+ {'x': 70, 'y': 1.0, 'orientation': 'standing'}
+ ]
+ vehicle_dict = {
+ 'position': [vehicle.pose.x, vehicle.pose.y],
+ 'heading': vehicle.pose.yaw,
+ 'velocity': vehicle.v
+ }
+ self.trajectory = plan_full_slalom_trajectory(vehicle_dict, cones)
+ self.planned = True
+ return self.trajectory
+
+
+# ------------ Test Code START --------------
+if __name__ == "__main__":
+ # --------------------------
+ # Plotting Function
+ # --------------------------
+ def plot_results(vehicle_state, cones, wpt_flexes=None, wpt_fixed=None, scenario_label=""):
+ plt.figure(figsize=(10, 5))
+ ax = plt.gca()
+ ax.set_aspect('equal')
+
+ all_x = [cone['x'] for cone in cones] + [vehicle_state['position'][0]]
+ all_y = [cone['y'] for cone in cones] + [vehicle_state['position'][1]]
+
+ if wpt_flexes is not None:
+ all_x += [pt[0] for pt in wpt_flexes]
+ all_y += [pt[1] for pt in wpt_flexes]
+
+ if wpt_fixed is not None:
+ all_x.append(wpt_fixed[0])
+ all_y.append(wpt_fixed[1])
+
+ # Compute axis limits with padding
+ padding = 2
+ x_min, x_max = min(all_x) - padding, max(all_x) + padding
+ y_min, y_max = min(all_y) - padding, max(all_y) + padding
+ plt.xlim(x_min, x_max)
+ plt.ylim(y_min, y_max)
+
+ # Plot cones
+ for cone in cones:
+ plt.scatter(cone['x'], cone['y'], c='orange', label='Cone' if cone == cones[0] else "")
+ plt.text(cone['x'], cone['y'] + 0.5, cone['orientation'][0].upper(), fontsize=10, ha='center')
+
+ # Plot vehicle
+ vx, vy = vehicle_state['position']
+ plt.plot(vx, vy, 'bo', label='Vehicle Start')
+ plt.arrow(vx, vy, np.cos(vehicle_state['heading']) * 2, np.sin(vehicle_state['heading']) * 2,
+ head_width=0.25, color='blue')
+
+ # Plot flexible waypoint
+ if wpt_flexes is not None:
+ for wpt_flex in wpt_flexes:
+ plt.plot(wpt_flex[0], wpt_flex[1], 'go', label='Flexible Waypoint')
+ plt.text(wpt_flex[0], wpt_flex[1] + 0.5, 'Flex', fontsize=9, color='green')
+
+ # Plot fixed waypoint
+ if wpt_fixed is not None:
+ plt.plot(wpt_fixed[0], wpt_fixed[1], 'ro', label='Fixed Waypoint')
+ plt.text(wpt_fixed[0], wpt_fixed[1] + 0.5, 'Fixed', fontsize=9, color='red')
+
+ plt.title(scenario_label)
+ plt.xlabel("X")
+ plt.ylabel("Y")
+ plt.grid(True)
+ plt.legend()
+ plt.show()
+ return
+
+ # --------------------------
+ # Vehicle State Test Update
+ # --------------------------
+ def drive(vehicle_state):
+ # Update vehicle state
+ vehicle_state['position'][0] += vehicle_state['velocity'] * np.cos(vehicle_state['heading'])
+ vehicle_state['position'][1] += vehicle_state['velocity'] * np.sin(vehicle_state['heading'])
+ return vehicle_state
+ # --------------------------
+ # Step 1: Generate Fake Cones
+ # --------------------------
+ def generate_test_cones(case='slalom'):
+ if case == 'slalom':
+ cones = []
+ for i in range(3):
+ x = (i+1) * 10
+ y = 0 if i % 2 == 0 else 1
+ orientation = 'left' if i % 2 == 0 else 'right'
+ cones.append({'x': x, 'y': y, 'orientation': orientation})
+ return cones
+
+ elif case == 'u_turn':
+ return [{'x': 10, 'y': 0, 'orientation': 'standing'}]
+
+ # --------------------------
+ # Step 2: Define Fake Vehicle
+ # --------------------------
+ def get_test_vehicle_state(vehicle_state=None):
+ if vehicle_state is not None:
+ return vehicle_state
+ return {
+ 'position': [0, 0],
+ 'heading': 0.0 * 180/np.pi, # Facing right
+ 'velocity': 10.0
+ }
+
+ # --------------------------
+ # Step 3: Run Scenario + Waypoints
+ # --------------------------
+ def test_waypoint_generation(case='slalom', test_loop=1):
+ vehicle_state = get_test_vehicle_state()
+ cones = generate_test_cones(case)
+
+ for i in range(test_loop):
+ scenario = scenario_check(vehicle_state, cones)
+ scenario_label = f"Scenario: {scenario}"
+ scenario, wpt_flexes, wpt_fixed = waypoint_generate(vehicle_state, cones)
+ plot_results(vehicle_state, cones, wpt_flexes, wpt_fixed, scenario_label)
+ vehicle_state = drive(vehicle_state)
+ if case == 'slalom':
+ cones.pop(0)
+
+ # --------------------------
+ # Main for waypoint
+ # --------------------------
+ # test_waypoint_generation(case='slalom', test_loop=2)
+ # test_waypoint_generation(case='u_turn')
+
+
+ # --------------------------
+ ### Combine Test
+ # --------------------------
+ def test_planning(case='slalom', test_loop=2):
+ vehicle_state = get_test_vehicle_state()
+ cones = generate_test_cones(case)
+
+ for i in range(test_loop):
+ # Way Points
+ scenario = scenario_check(vehicle_state, cones)
+ scenario_label = f"Scenario: {scenario}"
+ scenario, wpt_flexes, wpt_fixed = waypoint_generate(vehicle_state, cones)
+ plot_results(vehicle_state, cones, wpt_flexes, wpt_fixed, scenario_label)
+ # Trajectory
+ init_state = {'y': wpt_flexes[0][1], 'psi': 0.0, 'c': 0.0}
+ final_state = {'y': wpt_fixed[1], 'psi': 0.0, 'c': 0.0}
+
+ y_traj, psi_traj, c_traj, eps_traj = trajectory_generation(init_state, final_state)
+ # plot_trajectory(y_traj, psi_traj, c_traj, label="Generated trajectory")
+ # plot_dynamics(psi_traj, c_traj, eps_traj)
+
+ # Iterate
+ vehicle_state = drive(vehicle_state)
+ if case == 'slalom':
+ cones.pop(0)
+ # test_planning(case='slalom', test_loop=2)
+# ------------ Test Code END --------------
\ No newline at end of file
diff --git a/GEMstack/onboard/planning/racing_planning_online.py b/GEMstack/onboard/planning/racing_planning_online.py
new file mode 100644
index 000000000..6729d968e
--- /dev/null
+++ b/GEMstack/onboard/planning/racing_planning_online.py
@@ -0,0 +1,1048 @@
+from ...state.trajectory import Trajectory
+from ...state.vehicle import VehicleState
+from ...state import AgentState, AgentEnum
+from ..component import Component
+
+from ...state.trajectory import Trajectory, compute_headings, Path
+from ...state.physical_object import ObjectFrameEnum
+
+import numpy as np
+import matplotlib.pyplot as plt
+from scipy.optimize import minimize
+
+from typing import Dict
+import time
+
+# --------------------------
+# This is the main code for the racing trajectory planner.
+# Contributors: Hua-Ta, Shilan
+# --------------------------
+
+def scenario_check(vehicle_state, cone_state):
+ """
+ Check the cone state and determine the scenario.
+ Args:
+ vehicle_state: The state of the vehicle.
+ cone_state: The state of the cones.
+ Returns:
+ str: The scenario type.
+ - 'left_pass': cone pointed left, go left
+ - 'right_pass': cone pointed right, go right
+ - 'u_turn': cone standing up, make a U-turn
+ tuple: (cone_x, cone__y)
+ """
+ # Get the closest cone info
+ cones_ahead = sorted(cone_state, key=lambda c: np.linalg.norm(
+ np.array([c['x'], c['y']]) - np.array(vehicle_state['position'])))
+ cone_direction = cones_ahead[0]['orientation']
+ cone_position = (cones_ahead[0]['x'], cones_ahead[0]['y'])
+
+ # Check the cone orientation
+ if cone_direction != 'LEFT' and cone_direction != 'RIGHT' and cone_direction != 'STANDING' and cone_direction != '90turn':
+ raise ValueError("Unknown cone orientation")
+
+ return cone_direction, cone_position
+
+def waypoint_generate(vehicle_state, cones, cone_idx):
+ """
+ Generate waypoints based on the scenario.
+ Args:
+ vehicle_state: The state of the vehicle.
+ cone_state: The state of the cones.
+ Returns:
+ Tuple[str, Tuple[float, float], Tuple[float, float]]:
+ scenario: detected scenario type
+ flex_wp: flexible waypoint (used to maneuver)
+ fixed_wp: fixed waypoint (goal position)
+ """
+ scenario, cone_position = scenario_check(vehicle_state, [cones[cone_idx]])
+ car_position = np.array(vehicle_state['position'])
+ car_heading = vehicle_state['heading'] # in radians
+ current_heading = car_heading
+ target_heading = car_heading
+
+ # ===== Parameters =====
+ u_turn_radius = 11.5 # Radius for U-turn
+ offset = 2.0 # Offset for left/right pass
+ lookahead_distance = 10.0 # Distance ahead for fixed point
+ # ======================
+
+ # Direction vector based on heading
+ heading_vector = np.array([np.cos(car_heading), np.sin(car_heading)])
+
+ # Vector perpendicular to heading (to determine left/right)
+ perpendicular_vector = np.array([-np.sin(car_heading), np.cos(car_heading)])
+
+ if cone_idx > 0:
+ prev_cone_position = np.array((cones[cone_idx - 1]['x'], cones[cone_idx - 1]['y']))
+ cone_position = np.array((cones[cone_idx]['x'], cones[cone_idx]['y']))
+ target_heading = np.arctan2(cone_position[1] - prev_cone_position[1],
+ cone_position[0] - prev_cone_position[0])
+
+ if scenario == 'STANDING':
+ # U-turn: Generate points in a semi-circular arc around the cone
+ cone = np.array(cone_position)
+
+ # Number of waypoints to generate for the arc
+ num_arc_points = 9
+
+ # Generate waypoints in a smooth semi-circular pattern on the RIGHT side
+ flex_wps_list = []
+
+ # Create a semi-circular arc from 0 to π
+ # But negate perpendicular_vector to go to the right side
+ for i in range(num_arc_points):
+ # Calculate angle in the semi-circle (0 to π)
+ angle = i * np.pi * 1 / (num_arc_points - 1)
+
+ # MODIFIED: Negative perpendicular_vector to go to right side of cone
+ # This creates a counter-clockwise turn around the cone
+ wp = cone - u_turn_radius * (
+ perpendicular_vector * np.cos(angle) -
+ heading_vector * np.sin(angle)
+ )
+
+ flex_wps_list.append(wp)
+
+ # Fixed waypoint: behind the cone after U-turn (also on right side)
+ fixed_wp = cone + u_turn_radius * perpendicular_vector
+
+ target_heading = target_heading + np.pi
+
+ # For visualization only
+ # for i, wp in enumerate(flex_wps_list):
+ # plt.plot(wp[0], wp[1], 'ro') # Plot all waypoints in red
+ # plt.text(wp[0], wp[1], f'wp{i}', fontsize=9)
+
+ # plt.plot(fixed_wp[0], fixed_wp[1], 'bo') # Plot fixed waypoint in blue
+ # plt.plot(cone[0], cone[1], 'gx') # Plot cone in green
+ # plt.plot(car_position[0], car_position[1], 'ks') # Plot car position
+ # plt.axis('equal') # Equal aspect ratio for better visualization
+ # plt.grid(True)
+ # plt.show()
+
+ elif scenario == 'LEFT':
+ cone = np.array(cone_position)
+
+ # Flexible waypoint: go to the left of the cone
+ flex_wp1 = cone + offset * perpendicular_vector
+ flex_wps_list = [flex_wp1]
+
+ # Fixed waypoint: forward after passing the cone
+ # fixed_wp = flex_wp + heading_vector * lookahead_distance - offset * perpendicular_vector * 2
+ fixed_wp = flex_wp1 + heading_vector * lookahead_distance - offset * perpendicular_vector
+
+ elif scenario == 'RIGHT':
+ cone = np.array(cone_position)
+
+ # Flexible waypoint: go to the right of the cone
+ flex_wp1 = cone - offset * perpendicular_vector
+ flex_wps_list = [flex_wp1]
+
+ # Fixed waypoint: forward after passing the cone
+ # fixed_wp = flex_wp + heading_vector * lookahead_distance + offset * perpendicular_vector * 2
+ fixed_wp = flex_wp1 + heading_vector * lookahead_distance + offset * perpendicular_vector
+
+ # TODO: move to a different setting instead of as a scenario
+ elif scenario == '90turn':
+ turn_vector = np.array([-np.sin(car_heading + np.pi / 6), np.cos(car_heading + np.pi / 6)])
+ cone = np.array(cone_position)
+ distance_to_cone = np.linalg.norm(car_position - cone)
+
+ flex_wps_list = []
+ if distance_to_cone > 7:
+ steps = int(distance_to_cone // 6)
+ print("steps:", steps)
+
+ final_flex_wp = cone + 1.0 * perpendicular_vector + heading_vector * 1.0
+ fixed_wp = cone - turn_vector * 2.5 + heading_vector * 0.0
+
+ cone_direction = (final_flex_wp - car_position) / np.linalg.norm(final_flex_wp - car_position)
+ for i in range(steps - 2):
+ intermediate_wp = car_position + cone_direction * ((i + 1) * 6)
+ flex_wps_list.append(intermediate_wp)
+
+ flex_wps_list.append(final_flex_wp)
+ else:
+ flex_wp = cone + 1.0 * perpendicular_vector + heading_vector * 1.0
+ fixed_wp = cone - turn_vector * 2.5 + heading_vector * 0.0
+ flex_wps_list = [flex_wp]
+
+ else:
+ flex_wps_list = None
+ fixed_wp = None
+
+ target_heading = (target_heading + np.pi) % (2 * np.pi) - np.pi
+ current_heading = (current_heading + np.pi) % (2 * np.pi) - np.pi
+
+ if abs(target_heading - current_heading) > np.pi:
+ if target_heading < current_heading:
+ target_heading += 2 * np.pi
+ else:
+ target_heading -= 2 * np.pi
+
+ return scenario, flex_wps_list, fixed_wp, target_heading
+
+def trajectory_generation(init_state, final_state, N=30, T=0.1, Lr=1.5,
+ w_c=10.0, w_eps=0.0, w_vvar=4.0,
+ w_terminal=10.0,
+ v_min=3.0, v_max=11.0,
+ waypoints=None, waypoint_penalty_weight=100.0):
+ """
+ Generate a dynamically feasible trajectory between init_state and final_state
+ using curvature-based vehicle dynamics and nonlinear optimization.
+
+ Now supports multiple waypoints.
+
+ Parameters:
+ - init_state (dict): Initial vehicle state with keys 'x', 'y', 'psi', 'c', 'v'.
+ - final_state (dict): Target vehicle state with keys 'x', 'y', 'psi', 'c'.
+ - N (int): Number of discrete time steps in the trajectory.
+ - T (float): Duration of each time step (in seconds).
+ - Lr (float): Distance from the vehicle's center to the rear axle.
+ - w_c (float): Weight for penalizing curvature (smoothness of turns).
+ - w_eps (float): Weight for penalizing curvature rate (reduces sharp steering changes).
+ - w_vvar (float): Weight for penalizing speed variance (encourages speed smoothness).
+ - w_terminal (float): Weight for penalizing final state deviation (soft constraint).
+ - v_min (float): Minimum allowed speed (in m/s).
+ - v_max (float): Maximum allowed speed (in m/s).
+ - waypoints (list or None): Optional list of (x, y) coordinates that the trajectory should pass near.
+ - waypoint_penalty_weight (float): Penalty weight for distance from waypoints (soft constraint).
+
+ Returns:
+ - x, y, psi, c, v, eps (np.ndarray): Arrays of optimized state and control values.
+ - final_error (dict): Final state errors in x, y, psi, and c.
+ """
+ def cost(p):
+ x_, y_, psi_, c_, v_, eps_ = np.split(p, [N - 1, 2 * (N - 1), 3 * (N - 1), 4 * (N - 1), 5 * (N - 1)])
+ c_seq = np.concatenate(([init_state['c']], c_))
+ v_seq = np.concatenate(([init_state['v']], v_))
+ x_final, y_final, psi_final, c_final = x_[-1], y_[-1], psi_[-1], c_[-1]
+
+ cost_c = w_c * np.sum(c_seq ** 2)
+ cost_eps = w_eps * np.sum(eps_ ** 2)
+ v_mean = np.mean(v_seq)
+ cost_vvar = w_vvar * np.mean((v_seq - v_mean) ** 2)
+
+ cost_terminal = w_terminal * (
+ (x_final - final_state['x']) ** 2 +
+ (y_final - final_state['y']) ** 2 +
+ (psi_final - final_state['psi']) ** 2 * 100 +
+ (c_final - final_state['c']) ** 2 * 100
+ )
+
+ cost_waypoints = 0.0
+ if waypoints is not None and len(waypoints) > 0:
+ # Calculate equally spaced indices for each waypoint
+ num_waypoints = len(waypoints)
+ indices = [int((i + 1) * (N - 1) / (num_waypoints + 1)) for i in range(num_waypoints)]
+
+ # Sum penalties for each waypoint at its corresponding index
+ for wp_idx, waypoint in enumerate(waypoints):
+ traj_idx = indices[wp_idx]
+ cost_waypoints += waypoint_penalty_weight * (
+ (x_[traj_idx] - waypoint[0])**2 + (y_[traj_idx] - waypoint[1])**2
+ )
+
+ return cost_c + cost_eps + cost_vvar + cost_terminal + cost_waypoints
+ def dynamics_constraints(p):
+ x_, y_, psi_, c_, v_, eps_ = np.split(p, [N - 1, 2 * (N - 1), 3 * (N - 1), 4 * (N - 1), 5 * (N - 1)])
+ constraints = []
+ x_prev, y_prev, psi_prev, c_prev, v_prev = init_state['x'], init_state['y'], init_state['psi'], init_state['c'], init_state['v']
+ for k in range(N - 1):
+ dx = v_prev * np.cos(psi_prev + c_prev * Lr) * T
+ dy = v_prev * np.sin(psi_prev + c_prev * Lr) * T
+ dpsi = v_prev * c_prev * T
+ dc = eps_[k] * T
+ constraints.extend([
+ x_[k] - (x_prev + dx),
+ y_[k] - (y_prev + dy),
+ psi_[k] - (psi_prev + dpsi),
+ c_[k] - (c_prev + dc)
+ ])
+ x_prev, y_prev, psi_prev, c_prev, v_prev = x_[k], y_[k], psi_[k], c_[k], v_[k]
+ return constraints
+
+ # Initial guesses
+ x_vals = np.linspace(init_state['x'], final_state['x'], N)
+ y_vals = np.linspace(init_state['y'], final_state['y'], N)
+ psi_vals = np.linspace(init_state['psi'], final_state['psi'], N)
+ c_vals = np.linspace(init_state['c'], final_state['c'], N)
+ v_vals = np.ones(N) * init_state['v']
+ eps_vals = np.zeros(N - 1)
+
+ p0 = np.concatenate([x_vals[1:], y_vals[1:], psi_vals[1:], c_vals[1:], v_vals[1:], eps_vals])
+ bounds = [(None, None)] * (4 * (N - 1)) + [(v_min, v_max)] * (N - 1) + [(None, None)] * (N - 1)
+
+ result = minimize(cost, p0, bounds=bounds,
+ constraints={'type': 'eq', 'fun': dynamics_constraints},
+ options={'maxiter': 1000})
+ if not result.success:
+ raise RuntimeError("Optimization failed")
+
+ x_, y_, psi_, c_, v_, eps_ = np.split(result.x, [N - 1, 2 * (N - 1), 3 * (N - 1), 4 * (N - 1), 5 * (N - 1)])
+ x_full = np.concatenate(([init_state['x']], x_))
+ y_full = np.concatenate(([init_state['y']], y_))
+ psi_full = np.concatenate(([init_state['psi']], psi_))
+ c_full = np.concatenate(([init_state['c']], c_))
+ v_full = np.concatenate(([init_state['v']], v_))
+
+ final_error = {
+ 'x_error': abs(x_full[-1] - final_state['x']),
+ 'y_error': abs(y_full[-1] - final_state['y']),
+ 'psi_error': abs(psi_full[-1] - final_state['psi']),
+ 'c_error': abs(c_full[-1] - final_state['c']),
+ }
+
+ return x_full, y_full, psi_full, c_full, v_full, eps_, final_error
+
+def feasibility_check(trajectory, cone_map, car_width=2.0, safety_margin=0.3, v=10.0, Lr=1.5, T=0.1):
+ """
+ Check if the car trajectory collides with any cones.
+
+ Parameters:
+ - trajectory: list of (y, psi, c) states
+ - cone_map: list of (x, y) cone positions
+ - car_width: width of the vehicle in meters
+ - safety_margin: buffer around the vehicle
+ - v: vehicle constant speed (used for x position estimation)
+ - Lr: distance to rear axle
+ - T: time step
+
+ Returns:
+ - feasible: True if no collisions
+ - collisions: list of indices of cones that were collided with (for plotting purpose)
+ - x_vals, y_vals: trajectory positions for plotting (for plotting purpose)
+ """
+ y_vals, psi_vals, c_vals = zip(*trajectory)
+ x_vals = [0.0]
+ for i in range(1, len(trajectory)):
+ dx = v * np.cos(psi_vals[i-1] + c_vals[i-1] * Lr) * T
+ x_vals.append(x_vals[-1] + dx)
+
+ collision_radius = (car_width / 2.0) + safety_margin
+ collisions = []
+
+ for j, (cone_x, cone_y) in enumerate(cone_map):
+ for x, y in zip(x_vals, y_vals):
+ if np.hypot(x - cone_x, y - cone_y) < collision_radius:
+ collisions.append(j)
+ break
+
+ feasible = len(collisions) == 0
+ return feasible, collisions, x_vals, y_vals
+
+
+def waypoint_search_optimization(vehicle_state, cones, search_attempts=3):
+ valid_flex_wps = []
+ valid_fixed_wps = []
+ current_state = vehicle_state.copy()
+ cones_copy = cones.copy()
+
+ for i in range(min(search_attempts, len(cones_copy))):
+ scenario, flex_wps, fixed_wp = waypoint_generate(current_state, cones_copy)
+
+ if flex_wps is None or fixed_wp is None:
+ break
+
+ for flex_wp in flex_wps:
+ init_state = {
+ 'x': current_state['position'][0],
+ 'y': current_state['position'][1],
+ 'psi': current_state['heading'],
+ 'c': 0.0,
+ 'v': current_state['velocity']
+ }
+ final_state = {
+ 'x': fixed_wp[0],
+ 'y': fixed_wp[1],
+ 'psi': current_state['heading'],
+ 'c': 0.0
+ }
+
+ try:
+ x, y, psi, c, v, eps, final_error = trajectory_generation(init_state, final_state, waypoint=flex_wp)
+ trajectory = list(zip(y, psi, c))
+ feasible, collisions, x_vals, y_vals = feasibility_check(trajectory, [(cone['x'], cone['y']) for cone in cones])
+ # print(f"Checking waypoint: {flex_wp}, Fixed: {fixed_wp}, Feasible: {feasible}, Collisions: {collisions}")
+ if feasible:
+ valid_flex_wps.append(flex_wp)
+ valid_fixed_wps.append(fixed_wp)
+ current_state['position'] = list(fixed_wp)
+ break
+ except:
+ continue
+ if len(cones_copy) > 0:
+ cones_copy.pop(0)
+ return valid_flex_wps, valid_fixed_wps
+
+
+def to_gemstack_trajectory(x_all, y_all, v_all, T=0.1):
+ t_vals = np.arange(len(x_all)) * T
+ combined_xy = [[x, y] for x, y in zip(x_all, y_all)]
+ curr_path = Path(ObjectFrameEnum.START,combined_xy)
+ path = compute_headings(curr_path)
+ path_normalized = path.arc_length_parameterize()
+ points = [p for p in path_normalized.points]
+ return Trajectory(points=points, times=t_vals, frame=ObjectFrameEnum.START)
+
+
+def plan_full_slalom_trajectory(vehicle_state, cones, prev_conesID=None):
+ x_all, y_all, v_all = [], [], []
+ current_pos = np.array(vehicle_state['position'])
+ current_heading = vehicle_state['heading']
+ processed_coneIDs = []
+ count = 0
+ for cone_idx, cone in enumerate(cones):
+ if count == 1:
+ break
+ if (prev_conesID is not None) and (cone_idx in prev_conesID) :
+ continue
+ scenario, flex_wps, fixed_wp, target_heading = waypoint_generate(vehicle_state, cones, cone_idx)
+ print(f"Scenario: {scenario}, Cone: {cone}, Flex WP: {flex_wps}, Fixed WP: {fixed_wp}")
+ if not flex_wps or fixed_wp is None:
+ continue
+ # flex_wp = flex_wps[0]
+ current_heading = (current_heading + np.pi) % (2 * np.pi) - np.pi
+
+ init_state = {
+ 'x': current_pos[0], 'y': current_pos[1], 'psi': current_heading,
+ 'c': 0.0, 'v': vehicle_state['velocity']
+ }
+ final_state = {
+ 'x': fixed_wp[0], 'y': fixed_wp[1], 'psi': target_heading, 'c': 0.0
+ }
+
+ x, y, psi, c, v, eps, _ = trajectory_generation(init_state, final_state, waypoints=flex_wps)
+ x_all.extend(x)
+ y_all.extend(y)
+ v_all.extend(v)
+
+ current_pos = np.array([x[-1], y[-1]])
+ current_heading = psi[-1]
+ current_steering = c[-1]
+
+ vehicle_state = {
+ 'position': current_pos,
+ 'heading': current_heading,
+ 'velocity': v[-1]
+ }
+ current_pos = np.array([x[-1], y[-1]])
+ processed_coneIDs.append(cone_idx)
+ count += 1
+
+ # # Plot overall trajectory
+ # plt.figure()
+ # plt.plot(x_all, y_all, label='Overall Trajectory')
+
+ # # Plot cones
+ # for i, cone in enumerate(cones):
+ # plt.scatter(cone['x'], cone['y'], color='orange', s=10, label='Cone' if i == 0 else "")
+ # plt.text(cone['x'], cone['y'] + 0.5, f'C{i+1}', ha='center', fontsize=9, color='darkorange')
+
+ # plt.title('4-Cone Full Course Trajectory')
+ # plt.xlabel('X')
+ # plt.ylabel('Y')
+ # plt.legend()
+ # plt.axis('equal')
+ # plt.grid(True)
+ # plt.show()
+
+ combined_xy = [[x, y] for x, y in zip(x_all, y_all)]
+ # print(combined_xy)
+ path = Path(ObjectFrameEnum.START,combined_xy)
+ path = compute_headings(path)
+ path = path.arc_length_parameterize()
+ # print(path)
+ return path.racing_velocity_profile(), processed_coneIDs
+ # return to_gemstack_trajectory(x_all, y_all, v_all)
+
+
+def no_cone_planning(vehicle_dict):
+ temp_points = []
+ vehicle_x, vehicle_y = vehicle_dict['position'][0], vehicle_dict['position'][1]
+ vehicle_heading = vehicle_dict['heading']
+ vehicle_velocity = vehicle_dict['velocity']
+ step_size = 0.5 * (max(1,vehicle_velocity))
+ for i in range(10):
+ temp_points.append([vehicle_x + i * step_size * np.cos(vehicle_heading),
+ vehicle_y + i * step_size * np.sin(vehicle_heading)])
+
+ path = Path(ObjectFrameEnum.START,temp_points)
+ # print(temp_points)
+ path = compute_headings(path)
+ path = path.arc_length_parameterize()
+ # print(path)
+ return path.racing_velocity_profile()
+
+# def got_new_cone(current_cones, prev_cones):
+# if current_cones is None:
+# return False
+# if prev_cones is None:
+# return True
+# prev_ids = {cone['id'] for cone in prev_cones}
+
+# for cone in current_cones:
+# if cone['id'] not in prev_ids:
+# return True # Found a new cone not in previous list
+
+# return False
+################################################
+# Main Racing Trajectory Planner Class
+################################################
+class SlalomTrajectoryPlanner(Component):
+ def __init__(self, **kwargs):
+ # You can accept args here if needed
+ self.trajectory = None
+ self.prev_coneIDs = []
+ self.time = None
+ # ----------------------------
+ # Predifined-Cones Simulation
+ # self.run_fake_plan = True
+ # self.onboard = False
+
+ # # Onboard
+ self.run_fake_plan = False
+ self.onboard = True
+ # ----------------------------
+
+ self.DEBUG_MODE = True
+
+ def state_inputs(self):
+ return ['agents', 'vehicle'] # Receive VehicleState & AgentState input
+
+ def state_outputs(self):
+ return ['trajectory'] # Return trajectory output
+
+ def rate(self): # Setup the update rate
+ return 1.0
+
+ def update(self, agents: Dict[str, AgentState], vehicle: VehicleState):
+ # Running on real vehicle
+ if self.onboard:
+ # Get all current detected cones
+ cones = []
+ n = 0
+ now = time.time()
+
+ # Replan every 3 seconds
+ if self.time is None or now - self.time > 5:
+ self.time = now
+
+ for id, agent in agents.items():
+ if agent.type == AgentEnum.CONE:
+ # ===== RUNNING ONBOARD =====
+ # cones.append({
+ # 'id': id,
+ # 'x': agent.pose.x,
+ # 'y': agent.pose.y,
+ # 'orientation': agent.activity
+ # })
+ # ===== TESTING ONBOARD in BASIC SIM =====
+ if n % 2 == 0:
+ curr_activity = 'LEFT'
+ elif n % 2 == 1:
+ curr_activity = 'RIGHT'
+ else:
+ curr_activity = 'STANDING'
+ cones.append({
+ 'id': id,
+ 'x': agent.pose.x,
+ 'y': agent.pose.y,
+ 'orientation': curr_activity
+ })
+ n = n + 1
+
+ vehicle_dict = {
+ 'position': [vehicle.pose.x, vehicle.pose.y],
+ 'heading': vehicle.pose.yaw,
+ 'velocity': vehicle.v
+ }
+ if self.DEBUG_MODE:
+ print("===================== STATES =====================")
+ print(f"Vehicle State: {vehicle_dict}")
+ print(f"Detected Cones: {cones}")
+ print("===================== ====== =====================")
+ # If no cones detected, drive forward
+ if len(cones) == 0:
+ self.trajectory = no_cone_planning(vehicle_dict)
+ # Otherwise, plan trajectory
+ else:
+ self.trajectory, processed_ids = plan_full_slalom_trajectory(vehicle_dict, cones, self.prev_coneIDs)
+ self.prev_coneIDs = self.prev_coneIDs + processed_ids
+
+ # Testing with predefined fake generated cone positions
+ elif self.run_fake_plan:
+ # Example Test - Slalom
+ cones = [
+ {'x': 10, 'y': 0.0, 'orientation': 'LEFT'},
+ {'x': 30, 'y': 1.0, 'orientation': 'RIGHT'},
+ {'x': 50, 'y': 0.0, 'orientation': 'LEFT'},
+ {'x': 70, 'y': 1.0, 'orientation': 'STANDING'},
+ {'x': 50, 'y': 0.0, 'orientation': 'RIGHT'},
+ {'x': 30, 'y': 1.0, 'orientation': 'LEFT'},
+ {'x': 10, 'y': 0.0, 'orientation': 'RIGHT'}
+ ]
+ vehicle_dict = {
+ 'position': [vehicle.pose.x, vehicle.pose.y],
+ 'heading': vehicle.pose.yaw,
+ 'velocity': vehicle.v
+ }
+
+ # Example Test - Racing Circle
+ # cones = [
+ # {'x': -60.083, 'y': -33.118, 'orientation': '90turn'},
+ # {'x': -6.392, 'y': -5.147, 'orientation': '90turn'},
+ # {'x': -5.625, 'y': -13.637, 'orientation': '90turn'},
+ # {'x': -56.258, 'y': -41.080, 'orientation': '90turn'}
+ # ]
+ # vehicle_dict = {
+ # 'position': [-60.0, -39.0],
+ # 'heading': np.pi * 2 / 3,
+ # 'velocity': 0.0
+ # }
+
+ # Example Test - Racing Circle
+ # cones = [
+ # {'x': 0.0, 'y': 70.0, 'orientation': '90turn'},
+ # {'x': 30.0, 'y': 70.0, 'orientation': '90turn'},
+ # {'x': 30.0, 'y': 0.0, 'orientation': '90turn'},
+ # {'x': 0.0, 'y': 0.0, 'orientation': '90turn'}
+ # ]
+ # vehicle_dict = {
+ # 'position': [0.0, 20.0],
+ # 'heading': 0.0,
+ # 'velocity': 0.0
+ # }
+
+ self.trajectory = plan_full_slalom_trajectory(vehicle_dict, cones)
+ self.run_fake_plan = False
+
+ # Update output
+ return self.trajectory
+
+
+
+
+
+
+
+
+
+########################################################################################################################
+########################################################################################################################
+
+# ------------ Test Code START --------------
+
+# ======= Overall test cases to generate full trajectories with known cone positions =======
+def test_4_cone_slalom():
+ vehicle_state = {
+ 'position': [0.0, 0.0],
+ 'heading': 0.0,
+ 'velocity': 5.0
+ }
+
+ cones = [
+ {'x': 10, 'y': 0.0, 'orientation': 'left'},
+ {'x': 30, 'y': 1.0, 'orientation': 'right'},
+ {'x': 50, 'y': 0.0, 'orientation': 'left'},
+ {'x': 70, 'y': 1.0, 'orientation': 'standing'}
+ ]
+
+ flex_wps, fixed_wps = waypoint_search_optimization(vehicle_state, cones, search_attempts=1)
+
+ current_pos = np.array(vehicle_state['position'])
+
+ x_all, y_all = [], []
+
+ for idx, (flex_wp, fixed_wp) in enumerate(zip(flex_wps, fixed_wps)):
+ init_state = {
+ 'x': current_pos[0], 'y': current_pos[1], 'psi': vehicle_state['heading'],
+ 'c': 0.0, 'v': vehicle_state['velocity']
+ }
+ final_state = {
+ 'x': fixed_wp[0], 'y': fixed_wp[1], 'psi': vehicle_state['heading'], 'c': 0.0
+ }
+ x, y, psi, c, v, eps, final_error = trajectory_generation(init_state, final_state, waypoint=flex_wp)
+
+ print(f"\nSegment {idx + 1}:")
+ print(f" Waypoint: {flex_wp}")
+ print(f" Final Errors:")
+ for k, e in final_error.items():
+ print(f" {k}: {e:.4f}")
+
+ x_all += list(x)
+ y_all += list(y)
+
+ plot_trajectory(x, y, v, c, eps, waypoint=flex_wp)
+
+ current_pos = np.array(fixed_wp)
+
+ # Plot overall trajectory
+ plt.figure()
+ plt.plot(x_all, y_all, label='Overall Trajectory')
+
+ # Plot cones
+ for i, cone in enumerate(cones):
+ plt.scatter(cone['x'], cone['y'], color='orange', s=80, label='Cone' if i == 0 else "")
+ plt.text(cone['x'], cone['y'] + 0.5, f'C{i+1}', ha='center', fontsize=9, color='darkorange')
+
+ plt.title('4-Cone Full Course Trajectory')
+ plt.xlabel('X')
+ plt.ylabel('Y')
+ plt.legend()
+ plt.axis('equal')
+ plt.grid(True)
+ plt.show()
+
+########################
+if __name__ == "__main__":
+ def plot_trajectory(x, y, v, c, eps, waypoint=None):
+ plt.figure(figsize=(12, 10))
+
+ # Trajectory plot
+ plt.subplot(4, 1, 1)
+ plt.plot(x, y, label="Trajectory")
+ plt.scatter([x[0], x[-1]], [y[0], y[-1]], color='red', label="Start/End")
+
+ if waypoint is not None:
+ plt.scatter(*waypoint, color='purple', s=60, marker='X', label="Waypoint")
+ plt.annotate("Waypoint", (waypoint[0], waypoint[1]), textcoords="offset points", xytext=(5,5), color='purple')
+
+ plt.axis('equal')
+ plt.ylabel("y (m)")
+ plt.title("Trajectory")
+ plt.grid(True)
+ plt.legend()
+
+ # Speed plot
+ plt.subplot(4, 1, 2)
+ plt.plot(v, label="Speed (v)", color="blue")
+ plt.ylabel("Speed (m/s)")
+ plt.grid(True)
+ plt.legend()
+
+ # Curvature plot
+ plt.subplot(4, 1, 3)
+ plt.plot(c, label="Curvature (c)", color="orange")
+ plt.ylabel("Curvature (1/m)")
+ plt.grid(True)
+ plt.legend()
+
+ # Curvature rate plot
+ plt.subplot(4, 1, 4)
+ plt.plot(eps, label="Curvature Rate (ε)", color="green")
+ plt.xlabel("Step")
+ plt.ylabel("ε (1/m²)")
+ plt.grid(True)
+ plt.legend()
+
+ plt.tight_layout()
+ plt.show()
+
+ # --- Test Case 1: pass a cone in slalom ---
+ def trajectory_generation_test1():
+ # Init and final
+ init_state = {'x': 0.0, 'y': 0.0, 'psi': 0.0, 'c': 0.0, 'v': 5.0}
+ final_state = {'x': 15.0, 'y': 0.0, 'psi': np.pi / 20000000, 'c': np.pi / 20000000}
+ waypoint = (8.0, 6.0)
+
+ # Solve
+ x, y, psi, c, v, eps, final_error = trajectory_generation(
+ init_state, final_state, waypoint=waypoint
+ )
+ plot_trajectory(x, y, v, c, eps, waypoint)
+
+ # Error
+ print("\nFinal State Errors:")
+ for k, e in final_error.items():
+ print(f"{k}: {e:.6f}")
+
+ # --- Test case 2: 90 degree turn ---
+ def trajectory_generation_test2():
+ # Init and final
+ init_state = {'x': 0.0, 'y': 0.0, 'psi': 0.0, 'c': 0.0, 'v': 5.0}
+ final_state = {'x': 15.0, 'y': 15.0, 'psi': np.pi / 2, 'c': np.pi / 2}
+ waypoint = (13.0, 3.0)
+
+ # Solve
+ x, y, psi, c, v, eps, final_error = trajectory_generation(
+ init_state, final_state, waypoint=waypoint
+ )
+ plot_trajectory(x, y, v, c, eps, waypoint)
+
+ # Error
+ print("\nFinal State Errors:")
+ for k, e in final_error.items():
+ print(f"{k}: {e:.6f}")
+
+ #############
+ #########################
+ # --- Test Case ---
+ def test_feasibility_check():
+ N = 50
+ y_traj = np.linspace(0, 10, N)
+ psi_traj = np.linspace(0, 0.1, N)
+ c_traj = np.linspace(0, 0.2, N)
+ trajectory = list(zip(y_traj, psi_traj, c_traj))
+
+ # Cone map near the path
+ cone_map = [(5.0, 1.0), (10.0, 1.5), (15.0, 2.0), (25.0, 4.0), (25.0, 10.0), (16.0, 9.0), (40.0, 5.0)]
+
+ # Run check
+ feasible, collisions, x_vals, y_vals = feasibility_check(trajectory, cone_map)
+
+ # Plot
+ plt.figure(figsize=(10, 6))
+ plt.plot(x_vals, y_vals, label="Trajectory", linewidth=2)
+ for i, (cx, cy) in enumerate(cone_map):
+ color = 'red' if i in collisions else 'green'
+ plt.scatter(cx, cy, color=color, s=100, label=f'Cone {i}' if i == 0 else "")
+ plt.xlabel("x (m)")
+ plt.ylabel("y (m)")
+ plt.title("Trajectory and Cone Map")
+ plt.legend()
+ plt.axis("equal")
+ plt.grid(True)
+ plt.show()
+
+ print("Feasible:", feasible)
+ print("Collisions with cones:", collisions)
+
+
+# TODO 1: Compute target heading in waypoint_generation for different settings (slalom or course run)
+# TODO 2: Implement replanning
+def test_fixed_course():
+ # steering angle c is relative to car heading!!
+ vehicle_state = {
+ 'position': [-60.0, -39.0],
+ 'heading': np.pi * 2 / 3,
+ 'velocity': 0.0
+ }
+
+ cones = [
+ {'x': -60.083, 'y': -33.118, 'orientation': '90turn'},
+ {'x': -6.392, 'y': -5.147, 'orientation': '90turn'},
+ {'x': -5.625, 'y': -13.637, 'orientation': '90turn'},
+ {'x': -56.258, 'y': -41.080, 'orientation': '90turn'}
+ ]
+
+ current_pos = np.array(vehicle_state['position'])
+ current_heading = vehicle_state['heading']
+ current_steering = 0.0
+
+ x_all, y_all = [], []
+
+ for cone_idx, cone in enumerate(cones):
+ print("current cone: ", cone)
+ scenario, flex_wps, fixed_wp = waypoint_generate(vehicle_state, [cone])
+ if not flex_wps or fixed_wp is None:
+ continue
+
+ # Setting target_heading in final_state
+ if cone_idx > 0:
+ prev_cone_position = np.array((cones[cone_idx - 1]['x'], cones[cone_idx - 1]['y']))
+ current_cone_position = np.array((cones[cone_idx]['x'], cones[cone_idx]['y']))
+ target_heading = np.arctan2(current_cone_position[1] - prev_cone_position[1],
+ current_cone_position[0] - prev_cone_position[0]) - np.pi / 2 + np.pi / 18
+
+ else: # no previous cone
+ target_heading = current_heading - np.pi / 2 + np.pi / 18
+
+ # mod to -pi to pi range
+ target_heading = (target_heading + np.pi) % (2 * np.pi) - np.pi
+ current_heading = (current_heading + np.pi) % (2 * np.pi) - np.pi
+
+ if abs(target_heading - current_heading) > np.pi:
+ if target_heading < current_heading:
+ target_heading += 2 * np.pi
+ else:
+ target_heading -= 2 * np.pi
+
+ init_state = {
+ 'x': current_pos[0], 'y': current_pos[1], 'psi': current_heading,
+ 'c': current_steering, 'v': vehicle_state['velocity']
+ }
+
+ final_state = {
+ 'x': fixed_wp[0], 'y': fixed_wp[1], 'psi': target_heading, 'c': 0.0
+ }
+
+ estimated_N = int(((current_pos[0]-fixed_wp[0]) ** 2 + (current_pos[1]-fixed_wp[1]) ** 2) ** 0.5 / 0.7)
+
+ x, y, psi, c, v, eps, _ = trajectory_generation(init_state, final_state, waypoints=flex_wps, N=estimated_N)
+ x_all.extend(x)
+ y_all.extend(y)
+
+ plot_trajectory(x, y, v, c, eps)
+
+ current_pos = np.array([x[-1], y[-1]])
+ current_heading = psi[-1]
+ current_steering = c[-1]
+
+ vehicle_state = {
+ 'position': current_pos,
+ 'heading': current_heading,
+ 'velocity': v[-1]
+ }
+
+ # Plot overall trajectory
+ plt.figure()
+ plt.plot(x_all, y_all, label='Overall Trajectory')
+
+ # Plot cones
+ for i, cone in enumerate(cones):
+ plt.scatter(cone['x'], cone['y'], color='orange', s=10, label='Cone' if i == 0 else "")
+ plt.text(cone['x'], cone['y'] + 0.5, f'C{i+1}', ha='center', fontsize=9, color='darkorange')
+
+ plt.title('4-Cone Full Course Trajectory')
+ plt.xlabel('X')
+ plt.ylabel('Y')
+ plt.legend()
+ plt.axis('equal')
+ plt.grid(True)
+ plt.show()
+
+if __name__ == "__main__":
+ # --------------------------
+ # Plotting Function
+ # --------------------------
+ def plot_results(vehicle_state, cones, wpt_flexes=None, wpt_fixed=None, scenario_label=""):
+ plt.figure(figsize=(10, 5))
+ ax = plt.gca()
+ ax.set_aspect('equal')
+
+ all_x = [cone['x'] for cone in cones] + [vehicle_state['position'][0]]
+ all_y = [cone['y'] for cone in cones] + [vehicle_state['position'][1]]
+
+ if wpt_flexes is not None:
+ all_x += [pt[0] for pt in wpt_flexes]
+ all_y += [pt[1] for pt in wpt_flexes]
+
+ if wpt_fixed is not None:
+ all_x.append(wpt_fixed[0])
+ all_y.append(wpt_fixed[1])
+
+ # Compute axis limits with padding
+ padding = 2
+ x_min, x_max = min(all_x) - padding, max(all_x) + padding
+ y_min, y_max = min(all_y) - padding, max(all_y) + padding
+ plt.xlim(x_min, x_max)
+ plt.ylim(y_min, y_max)
+
+ # Plot cones
+ for cone in cones:
+ plt.scatter(cone['x'], cone['y'], c='orange', label='Cone' if cone == cones[0] else "")
+ plt.text(cone['x'], cone['y'] + 0.5, cone['orientation'][0].upper(), fontsize=10, ha='center')
+
+ # Plot vehicle
+ vx, vy = vehicle_state['position']
+ plt.plot(vx, vy, 'bo', label='Vehicle Start')
+ plt.arrow(vx, vy, np.cos(vehicle_state['heading']) * 2, np.sin(vehicle_state['heading']) * 2,
+ head_width=0.25, color='blue')
+
+ # Plot flexible waypoint
+ if wpt_flexes is not None:
+ for wpt_flex in wpt_flexes:
+ plt.plot(wpt_flex[0], wpt_flex[1], 'go', label='Flexible Waypoint')
+ plt.text(wpt_flex[0], wpt_flex[1] + 0.5, 'Flex', fontsize=9, color='green')
+
+ # Plot fixed waypoint
+ if wpt_fixed is not None:
+ plt.plot(wpt_fixed[0], wpt_fixed[1], 'ro', label='Fixed Waypoint')
+ plt.text(wpt_fixed[0], wpt_fixed[1] + 0.5, 'Fixed', fontsize=9, color='red')
+
+ plt.title(scenario_label)
+ plt.xlabel("X")
+ plt.ylabel("Y")
+ plt.grid(True)
+ plt.legend()
+ plt.show()
+ return
+
+ # --------------------------
+ # Vehicle State Test Update
+ # --------------------------
+ def drive(vehicle_state):
+ # Update vehicle state
+ vehicle_state['position'][0] += vehicle_state['velocity'] * np.cos(vehicle_state['heading'])
+ vehicle_state['position'][1] += vehicle_state['velocity'] * np.sin(vehicle_state['heading'])
+ return vehicle_state
+ # --------------------------
+ # Step 1: Generate Fake Cones
+ # --------------------------
+ def generate_test_cones(case='slalom'):
+ if case == 'slalom':
+ cones = []
+ for i in range(3):
+ x = (i+1) * 10
+ y = 0 if i % 2 == 0 else 1
+ orientation = 'left' if i % 2 == 0 else 'right'
+ cones.append({'x': x, 'y': y, 'orientation': orientation})
+ return cones
+
+ elif case == 'u_turn':
+ return [{'x': 10, 'y': 0, 'orientation': 'standing'}]
+
+ # --------------------------
+ # Step 2: Define Fake Vehicle
+ # --------------------------
+ def get_test_vehicle_state(vehicle_state=None):
+ if vehicle_state is not None:
+ return vehicle_state
+ return {
+ 'position': [0, 0],
+ 'heading': 0.0 * 180/np.pi, # Facing right
+ 'velocity': 10.0
+ }
+
+ # --------------------------
+ # Step 3: Run Scenario + Waypoints
+ # --------------------------
+ def test_waypoint_generation(case='slalom', test_loop=1):
+ vehicle_state = get_test_vehicle_state()
+ cones = generate_test_cones(case)
+
+ for i in range(test_loop):
+ scenario = scenario_check(vehicle_state, cones)
+ scenario_label = f"Scenario: {scenario}"
+ scenario, wpt_flexes, wpt_fixed = waypoint_generate(vehicle_state, cones)
+ plot_results(vehicle_state, cones, wpt_flexes, wpt_fixed, scenario_label)
+ vehicle_state = drive(vehicle_state)
+ if case == 'slalom':
+ cones.pop(0)
+
+ # --------------------------
+ # Main for waypoint
+ # --------------------------
+ # test_waypoint_generation(case='slalom', test_loop=2)
+ # test_waypoint_generation(case='u_turn')
+
+
+ # --------------------------
+ ### Combine Test
+ # --------------------------
+ def test_planning(case='slalom', test_loop=2):
+ vehicle_state = get_test_vehicle_state()
+ cones = generate_test_cones(case)
+
+ for i in range(test_loop):
+ # Way Points
+ scenario = scenario_check(vehicle_state, cones)
+ scenario_label = f"Scenario: {scenario}"
+ scenario, wpt_flexes, wpt_fixed = waypoint_generate(vehicle_state, cones)
+ plot_results(vehicle_state, cones, wpt_flexes, wpt_fixed, scenario_label)
+ # Trajectory
+ init_state = {'y': wpt_flexes[0][1], 'psi': 0.0, 'c': 0.0}
+ final_state = {'y': wpt_fixed[1], 'psi': 0.0, 'c': 0.0}
+
+ y_traj, psi_traj, c_traj, eps_traj = trajectory_generation(init_state, final_state)
+ # plot_trajectory(y_traj, psi_traj, c_traj, label="Generated trajectory")
+ # plot_dynamics(psi_traj, c_traj, eps_traj)
+
+ # Iterate
+ vehicle_state = drive(vehicle_state)
+ if case == 'slalom':
+ cones.pop(0)
+ # test_planning(case='slalom', test_loop=2)
+# ------------ Test Code END --------------
\ No newline at end of file
diff --git a/GEMstack/onboard/planning/racing_planning_trajectory.py b/GEMstack/onboard/planning/racing_planning_trajectory.py
new file mode 100644
index 000000000..1886e41f7
--- /dev/null
+++ b/GEMstack/onboard/planning/racing_planning_trajectory.py
@@ -0,0 +1,196 @@
+import numpy as np
+import matplotlib.pyplot as plt
+from scipy.optimize import minimize
+
+def trajectory_generation(init_state, final_state, w_c=1.0, w_eps=1.0):
+ N = 50
+ T = 0.1
+ v = 10.0
+ Lr = 1.5
+ small_constant = 1e-3
+
+ def optimize_with_weights(dynamic_weights_c=None, dynamic_weights_eps=None):
+ y = np.linspace(init_state['y'], final_state['y'], N)
+ psi = np.linspace(init_state['psi'], final_state['psi'], N)
+ c = np.linspace(init_state['c'], final_state['c'], N)
+ eps = np.zeros(N - 1)
+
+ def cost(x):
+ y_, psi_, c_, eps_ = np.split(x, [N-1, 2*(N-1), 3*(N-1)])
+ c_seq = np.concatenate(([init_state['c']], c_))
+ cost_c = np.sum((dynamic_weights_c if dynamic_weights_c is not None else w_c) * c_seq**2)
+ cost_eps = np.sum((dynamic_weights_eps if dynamic_weights_eps is not None else w_eps) * eps_**2)
+ return cost_c + cost_eps
+
+ def dynamics_constraints(x):
+ y_, psi_, c_, eps_ = np.split(x, [N-1, 2*(N-1), 3*(N-1)])
+ constraints = []
+ y_prev, psi_prev, c_prev = init_state['y'], init_state['psi'], init_state['c']
+ for k in range(N-1):
+ dy = v * np.sin(psi_prev + c_prev * Lr) * T
+ dpsi = v * c_prev * T
+ dc = eps_[k] * T
+ constraints.append(y_[k] - (y_prev + dy))
+ constraints.append(psi_[k] - (psi_prev + dpsi))
+ constraints.append(c_[k] - (c_prev + dc))
+ y_prev, psi_prev, c_prev = y_[k], psi_[k], c_[k]
+ constraints.append(y_[-1] - final_state['y'])
+ constraints.append(psi_[-1] - final_state['psi'])
+ constraints.append(c_[-1] - final_state['c'])
+ return constraints
+
+ x0 = np.concatenate([y[1:], psi[1:], c[1:], eps])
+ result = minimize(cost, x0, constraints={'type': 'eq', 'fun': dynamics_constraints}, options={'maxiter': 1000})
+
+ if result.success:
+ y_, psi_, c_, eps_ = np.split(result.x, [N-1, 2*(N-1), 3*(N-1)])
+ y_full = np.concatenate(([init_state['y']], y_))
+ psi_full = np.concatenate(([init_state['psi']], psi_))
+ c_full = np.concatenate(([init_state['c']], c_))
+ return y_full, psi_full, c_full, eps_
+ else:
+ raise RuntimeError("Optimization failed")
+
+ # First pass
+ y1, psi1, c1, eps1 = optimize_with_weights()
+
+ # Shape weights based on result
+ dynamic_weights_c = np.abs(c1) + small_constant
+ dynamic_weights_eps = np.abs(eps1) + small_constant
+
+ # Second pass with weighted cost
+ y2, psi2, c2, eps2 = optimize_with_weights(dynamic_weights_c, dynamic_weights_eps)
+ return y2, psi2, c2, eps2
+
+def plot_trajectory(y_traj, psi_traj, c_traj, label):
+ N = len(y_traj)
+ T = 0.1
+ v = 5.0
+ x_traj = np.zeros(N)
+ for i in range(1, N):
+ dx = v * np.cos(psi_traj[i-1] + c_traj[i-1] * 1.5) * T
+ x_traj[i] = x_traj[i-1] + dx
+
+ plt.figure(figsize=(8, 5))
+ plt.plot(x_traj, y_traj, label=label)
+ plt.scatter([x_traj[0], x_traj[-1]], [y_traj[0], y_traj[-1]], color='red', zorder=5)
+ plt.annotate("init", (x_traj[0], y_traj[0]), textcoords="offset points", xytext=(-10,10), ha='center')
+ plt.annotate("final", (x_traj[-1], y_traj[-1]), textcoords="offset points", xytext=(10,10), ha='center')
+ plt.xlabel('x (m)')
+ plt.ylabel('y (m)')
+ plt.title('Trajectory from Initial to Final State')
+ plt.legend()
+ plt.axis('equal')
+ plt.grid(True)
+ plt.show()
+
+def plot_dynamics(psi_traj, c_traj, eps_traj):
+ time_steps = np.arange(len(psi_traj))
+ eps_time = np.arange(len(eps_traj))
+
+ plt.figure(figsize=(12, 8))
+
+ plt.subplot(3, 1, 1)
+ plt.plot(time_steps, psi_traj, label="Heading (ψ)")
+ plt.ylabel("ψ (rad)")
+ plt.grid(True)
+ plt.legend()
+
+ plt.subplot(3, 1, 2)
+ plt.plot(time_steps, c_traj, label="Curvature (c)", color='orange')
+ plt.ylabel("Curvature (1/m)")
+ plt.grid(True)
+ plt.legend()
+
+ plt.subplot(3, 1, 3)
+ plt.plot(eps_time, eps_traj, label="Curvature Rate (ε)", color='green')
+ plt.xlabel("Time Step")
+ plt.ylabel("ε (1/m²)")
+ plt.grid(True)
+ plt.legend()
+
+ plt.tight_layout()
+ plt.show()
+
+# --- Test Case ---
+def test_trajectory_generation():
+ init_state = {'y': 0.0, 'psi': 0.0, 'c': 0.0}
+ final_state = {'y': 10.0, 'psi': 0.0, 'c': 0.0}
+
+ y_traj, psi_traj, c_traj, eps_traj = trajectory_generation(init_state, final_state)
+ plot_trajectory(y_traj, psi_traj, c_traj, label="Generated trajectory")
+ plot_dynamics(psi_traj, c_traj, eps_traj)
+
+
+
+
+def feasibility_check(trajectory, cone_map, car_width=2.0, safety_margin=0.3, v=10.0, Lr=1.5, T=0.1):
+ """
+ Check if the car trajectory collides with any cones.
+
+ Parameters:
+ - trajectory: list of (y, psi, c) states
+ - cone_map: list of (x, y) cone positions
+ - car_width: width of the vehicle in meters
+ - safety_margin: buffer around the vehicle
+ - v: vehicle constant speed (used for x position estimation)
+ - Lr: distance to rear axle
+ - T: time step
+
+ Returns:
+ - feasible: True if no collisions
+ - collisions: list of indices of cones that were collided with (for plotting purpose)
+ - x_vals, y_vals: trajectory positions for plotting (for plotting purpose)
+ """
+ y_vals, psi_vals, c_vals = zip(*trajectory)
+ x_vals = [0.0]
+ for i in range(1, len(trajectory)):
+ dx = v * np.cos(psi_vals[i-1] + c_vals[i-1] * Lr) * T
+ x_vals.append(x_vals[-1] + dx)
+
+ collision_radius = (car_width / 2.0) + safety_margin
+ collisions = []
+
+ for j, (cone_x, cone_y) in enumerate(cone_map):
+ for x, y in zip(x_vals, y_vals):
+ if np.hypot(x - cone_x, y - cone_y) < collision_radius:
+ collisions.append(j)
+ break
+
+ feasible = len(collisions) == 0
+ return feasible, collisions, x_vals, y_vals
+
+# --- Test Case ---
+def test_feasibility_check():
+ N = 50
+ y_traj = np.linspace(0, 10, N)
+ psi_traj = np.linspace(0, 0.1, N)
+ c_traj = np.linspace(0, 0.2, N)
+ trajectory = list(zip(y_traj, psi_traj, c_traj))
+
+ # Cone map near the path
+ cone_map = [(5.0, 1.0), (10.0, 1.5), (15.0, 2.0), (25.0, 4.0), (25.0, 10.0), (16.0, 9.0), (40.0, 5.0)]
+
+ # Run check
+ feasible, collisions, x_vals, y_vals = feasibility_check(trajectory, cone_map)
+
+ # Plot
+ plt.figure(figsize=(10, 6))
+ plt.plot(x_vals, y_vals, label="Trajectory", linewidth=2)
+ for i, (cx, cy) in enumerate(cone_map):
+ color = 'red' if i in collisions else 'green'
+ plt.scatter(cx, cy, color=color, s=100, label=f'Cone {i}' if i == 0 else "")
+ plt.xlabel("x (m)")
+ plt.ylabel("y (m)")
+ plt.title("Trajectory and Cone Map")
+ plt.legend()
+ plt.axis("equal")
+ plt.grid(True)
+ plt.show()
+
+ print("Feasible:", feasible)
+ print("Collisions with cones:", collisions)
+
+if __name__ == "__main__":
+ test_trajectory_generation()
+ test_feasibility_check()
\ No newline at end of file
diff --git a/GEMstack/onboard/planning/racing_planning_waypoint.py b/GEMstack/onboard/planning/racing_planning_waypoint.py
new file mode 100644
index 000000000..950911c71
--- /dev/null
+++ b/GEMstack/onboard/planning/racing_planning_waypoint.py
@@ -0,0 +1,256 @@
+# from typing import List, Tuple, Union
+# from ..component import Component
+# from ...state import AllState, VehicleState, EntityRelation, EntityRelationEnum, Path, Trajectory, Route, ObjectFrameEnum, AgentState
+# from ...utils import serialization, settings
+# from ...mathutils.transforms import vector_madd
+# from ...mathutils.quadratic_equation import quad_root
+
+# ===== Additional Imports =====
+import numpy as np
+import matplotlib.pyplot as plt
+from scipy.optimize import minimize
+# ==============================
+
+#TODO: Combine with current planner and GemStack
+# def longitudinal_plan(path : Path, acceleration : float, deceleration : float, max_speed : float, current_speed : float,
+# method : str) -> Trajectory:
+
+# return Trajectory(frame=path.frame, points=dense_points, times=times)
+
+def scenario_check(vehicle_state, cone_state):
+ """
+ Check the cone state and determine the scenario.
+ Args:
+ vehicle_state: The state of the vehicle.
+ cone_state: The state of the cones.
+ Returns:
+ str: The scenario type.
+ - 'left_pass': cone pointed left, go left
+ - 'right_pass': cone pointed right, go right
+ - 'u_turn': cone standing up, make a U-turn
+ tuple: (cone_x, cone__y)
+ """
+ # Get the closest cone info
+ cones_ahead = sorted(cone_state, key=lambda c: np.linalg.norm(
+ np.array([c['x'], c['y']]) - np.array(vehicle_state['position'])))
+ cone_direction = cones_ahead[0]['orientation']
+ cone_position = (cones_ahead[0]['x'], cones_ahead[0]['y'])
+
+ # Check the cone orientation
+ if cone_direction != 'left' and cone_direction != 'right' and cone_direction != 'standing':
+ raise ValueError("Unknown cone orientation")
+
+ return cone_direction, cone_position
+
+def waypoint_generate(vehicle_state, cone_state):
+ """
+ Generate waypoints based on the scenario.
+ Args:
+ vehicle_state: The state of the vehicle.
+ cone_state: The state of the cones.
+ Returns:
+ Tuple[str, Tuple[float, float], Tuple[float, float]]:
+ scenario: detected scenario type
+ flex_wp: flexible waypoint (used to maneuver)
+ fixed_wp: fixed waypoint (goal position)
+ """
+ scenario, cone_position = scenario_check(vehicle_state, cone_state)
+ car_position = np.array(vehicle_state['position'])
+ car_heading = vehicle_state['heading'] # in radians
+
+ # ===== Parameters =====
+ u_turn_radius = 5.0 # Radius for U-turn
+ offset = 2.0 # Offset for left/right pass
+ lookahead_distance = 5.0 # Distance ahead for fixed point
+ # ======================
+
+ # Direction vector based on heading
+ heading_vector = np.array([np.cos(car_heading), np.sin(car_heading)])
+
+ # Vector perpendicular to heading (to determine left/right)
+ perpendicular_vector = np.array([-np.sin(car_heading), np.cos(car_heading)])
+
+ if scenario == 'standing':
+ # U-turn: Circle around the cone
+ cone = np.array(cone_position)
+
+ # Flexible waypoint: halfway between car and a point offset from cone center
+ flex_wp1 = cone + u_turn_radius * perpendicular_vector
+ flex_wp2 = cone + heading_vector * lookahead_distance
+ flex_wps = [flex_wp1, flex_wp2]
+
+ # Fixed waypoint: behind the cone after U-turn
+ # fixed_wp = cone - heading_vector * lookahead_distance
+ fixed_wp = cone - u_turn_radius * perpendicular_vector
+
+ elif scenario == 'left':
+ cone = np.array(cone_position)
+
+ # Flexible waypoint: go to the left of the cone
+ flex_wp1 = cone + offset * perpendicular_vector
+ flex_wps = [flex_wp1]
+
+ # Fixed waypoint: forward after passing the cone
+ # fixed_wp = flex_wp + heading_vector * lookahead_distance - offset * perpendicular_vector * 2
+ fixed_wp = flex_wp1 + heading_vector * lookahead_distance - offset * perpendicular_vector
+
+ elif scenario == 'right':
+ cone = np.array(cone_position)
+
+ # Flexible waypoint: go to the right of the cone
+ flex_wp1 = cone - offset * perpendicular_vector
+ flex_wps = [flex_wp1]
+
+ # Fixed waypoint: forward after passing the cone
+ # fixed_wp = flex_wp + heading_vector * lookahead_distance + offset * perpendicular_vector * 2
+ fixed_wp = flex_wp1 + heading_vector * lookahead_distance + offset * perpendicular_vector
+
+ else:
+ flex_wps = None
+ fixed_wp = None
+
+ return scenario, flex_wps, fixed_wp
+
+def velocity_profiling(path, acceleration, deceleration, max_speed, current_speed, lateral_acc_limit):
+ """
+ Returns a trajectory with velocity profile that respects:
+ 1. max longitudinal acceleration
+ 2. max deceleration
+ 3. max lateral acceleration from curvature
+ 4. max speed
+ """
+ # Curvature-based speed limit
+ curvature_safe_speeds = []
+ for p in path.curvature:
+ if abs(p) < 1e-3:
+ curvature_safe_speeds.append(max_speed)
+ else:
+ max_v = np.sqrt(lateral_acc_limit / abs(p))
+ curvature_safe_speeds.append(min(max_v, max_speed))
+
+ # Create a custom profile-aware speed function
+ def dynamic_max_speed_at(index):
+ return curvature_safe_speeds[min(index, len(curvature_safe_speeds) - 1)]
+
+ # You can inject dynamic speed limit into your plan
+ return
+
+
+# ------------ Test Code --------------
+if __name__ == "__main__":
+ import matplotlib.pyplot as plt
+ import numpy as np
+
+ # --------------------------
+ # Plotting Function
+ # --------------------------
+ def plot_results(vehicle_state, cones, wpt_flexes=None, wpt_fixed=None, scenario_label=""):
+ plt.figure(figsize=(10, 5))
+ ax = plt.gca()
+ ax.set_aspect('equal')
+
+ all_x = [cone['x'] for cone in cones] + [vehicle_state['position'][0]]
+ all_y = [cone['y'] for cone in cones] + [vehicle_state['position'][1]]
+
+ if wpt_flexes is not None:
+ all_x += [pt[0] for pt in wpt_flexes]
+ all_y += [pt[1] for pt in wpt_flexes]
+
+ if wpt_fixed is not None:
+ all_x.append(wpt_fixed[0])
+ all_y.append(wpt_fixed[1])
+
+ # Compute axis limits with padding
+ padding = 2
+ x_min, x_max = min(all_x) - padding, max(all_x) + padding
+ y_min, y_max = min(all_y) - padding, max(all_y) + padding
+ plt.xlim(x_min, x_max)
+ plt.ylim(y_min, y_max)
+
+ # Plot cones
+ for cone in cones:
+ plt.scatter(cone['x'], cone['y'], c='orange', label='Cone' if cone == cones[0] else "")
+ plt.text(cone['x'], cone['y'] + 0.5, cone['orientation'][0].upper(), fontsize=10, ha='center')
+
+ # Plot vehicle
+ vx, vy = vehicle_state['position']
+ plt.plot(vx, vy, 'bo', label='Vehicle Start')
+ plt.arrow(vx, vy, np.cos(vehicle_state['heading']) * 2, np.sin(vehicle_state['heading']) * 2,
+ head_width=0.25, color='blue')
+
+ # Plot flexible waypoint
+ if wpt_flexes is not None:
+ for wpt_flex in wpt_flexes:
+ plt.plot(wpt_flex[0], wpt_flex[1], 'go', label='Flexible Waypoint')
+ plt.text(wpt_flex[0], wpt_flex[1] + 0.5, 'Flex', fontsize=9, color='green')
+
+ # Plot fixed waypoint
+ if wpt_fixed is not None:
+ plt.plot(wpt_fixed[0], wpt_fixed[1], 'ro', label='Fixed Waypoint')
+ plt.text(wpt_fixed[0], wpt_fixed[1] + 0.5, 'Fixed', fontsize=9, color='red')
+
+ plt.title(scenario_label)
+ plt.xlabel("X")
+ plt.ylabel("Y")
+ plt.grid(True)
+ plt.legend()
+ plt.show()
+ return
+
+ # --------------------------
+ # Vehicle State Test Update
+ # --------------------------
+ def drive(vehicle_state):
+ # Update vehicle state
+ vehicle_state['position'][0] += vehicle_state['velocity'] * np.cos(vehicle_state['heading'])
+ vehicle_state['position'][1] += vehicle_state['velocity'] * np.sin(vehicle_state['heading'])
+ return vehicle_state
+ # --------------------------
+ # Step 1: Generate Fake Cones
+ # --------------------------
+ def generate_test_cones(case='slalom'):
+ if case == 'slalom':
+ cones = []
+ for i in range(3):
+ x = (i+1) * 10
+ y = 0 if i % 2 == 0 else 1
+ orientation = 'left' if i % 2 == 0 else 'right'
+ cones.append({'x': x, 'y': y, 'orientation': orientation})
+ return cones
+
+ elif case == 'u_turn':
+ return [{'x': 10, 'y': 0, 'orientation': 'standing'}]
+
+ # --------------------------
+ # Step 2: Define Fake Vehicle
+ # --------------------------
+ def get_test_vehicle_state(vehicle_state=None):
+ if vehicle_state is not None:
+ return vehicle_state
+ return {
+ 'position': [0, 0],
+ 'heading': 0.0 * 180/np.pi, # Facing right
+ 'velocity': 10.0
+ }
+
+ # --------------------------
+ # Step 3: Run Scenario + Waypoints
+ # --------------------------
+ def test_waypoint_generation(case='slalom', test_loop=1):
+ vehicle_state = get_test_vehicle_state()
+ cones = generate_test_cones(case)
+
+ for i in range(test_loop):
+ scenario = scenario_check(vehicle_state, cones)
+ scenario_label = f"Scenario: {scenario}"
+ scenario, wpt_flexes, wpt_fixed = waypoint_generate(vehicle_state, cones)
+ plot_results(vehicle_state, cones, wpt_flexes, wpt_fixed, scenario_label)
+ vehicle_state = drive(vehicle_state)
+ if case == 'slalom':
+ cones.pop(0)
+
+ # --------------------------
+ # Main for waypoint
+ # --------------------------
+ test_waypoint_generation(case='slalom', test_loop=2)
+ test_waypoint_generation(case='u_turn')
diff --git a/GEMstack/onboard/planning/stanley.py b/GEMstack/onboard/planning/stanley.py
new file mode 100644
index 000000000..f00fdff5a
--- /dev/null
+++ b/GEMstack/onboard/planning/stanley.py
@@ -0,0 +1,402 @@
+import numpy as np
+import rospy
+from math import sin, cos, atan2
+
+# These imports match your existing project structure
+from ...mathutils.control import PID
+from ...utils import settings
+from ...mathutils import transforms
+from ...knowledge.vehicle.geometry import front2steer
+from ...knowledge.vehicle.dynamics import acceleration_to_pedal_positions
+from ...state.vehicle import VehicleState, ObjectFrameEnum
+from ...state.trajectory import Path, Trajectory
+from ..interface.gem import GEMVehicleCommand
+from ..component import Component
+
+#####################################
+# 1. Angle normalization
+#####################################
+def normalise_angle(angle):
+ """Wraps an angle to the [-pi, pi] range."""
+ while angle > np.pi:
+ angle -= 2.0 * np.pi
+ while angle < -np.pi:
+ angle += 2.0 * np.pi
+ return angle
+
+#####################################
+# 2. Stanley-based controller with longitudinal PID
+#####################################
+class Stanley(object):
+ """
+ A Stanley controller that handles lateral control (steering)
+ plus a basic longitudinal control (PID + optional feedforward).
+ It has been modified to reduce oscillations by:
+ 1) Lower gains
+ 2) Steering damping
+ 3) Low-pass filter on steering
+ 4) Gentler speed logic when cornering
+ """
+
+ def __init__(
+ self,
+ control_gain=None,
+ softening_gain=None,
+ desired_speed=None
+ ):
+ """
+ :param control_gain: Stanley lateral control gain k (lowered from the default to reduce overshoot).
+ :param softening_gain: Softening gain k_soft.
+ :param yaw_rate_gain: Yaw-rate gain k_yaw_rate (helps reduce oscillations).
+ :param steering_damp_gain: Steering damping gain k_damp_steer.
+ :param desired_speed: Desired speed (float) or 'path'/'trajectory'.
+ """
+
+ # 1) Lower Gains
+ self.k = control_gain if control_gain is not None else settings.get('control.stanley.control_gain')
+ self.k_soft = softening_gain if softening_gain is not None else settings.get('control.stanley.softening_gain')
+
+ # Typically, this is the max front-wheel steering angle in radians
+ self.max_steer = settings.get('vehicle.geometry.max_wheel_angle')
+ self.wheelbase = settings.get('vehicle.geometry.wheelbase')
+
+ # Basic longitudinal constraints
+ self.speed_limit = settings.get('vehicle.limits.max_speed')
+ self.max_accel = settings.get('vehicle.limits.max_acceleration')
+ self.max_decel = settings.get('vehicle.limits.max_deceleration')
+
+ # PID for longitudinal speed tracking
+ p = settings.get('control.longitudinal_control.pid_p')
+ d = settings.get('control.longitudinal_control.pid_d')
+ i = settings.get('control.longitudinal_control.pid_i')
+ self.pid_speed = PID(p, d, i, windup_limit=20)
+
+ self.stage_duration = settings.get('control.launch_control.stage_duration', 0.5)
+ self.launch_start_time = None
+
+ # Speed source: numeric or derived from path/trajectory
+ if desired_speed is not None:
+ self.desired_speed_source = desired_speed
+ else:
+ self.desired_speed_source = settings.get('control.stanley.desired_speed', 'path')
+
+ if isinstance(self.desired_speed_source, (int, float)):
+ self.desired_speed = self.desired_speed_source
+ else:
+ self.desired_speed = None
+
+ # For path/trajectory
+ self.path_arg = None
+ self.path = None
+ self.trajectory = None
+ self.current_path_parameter = 0.0
+ self.current_traj_parameter = 0.0
+ self.t_last = None
+
+ def set_path(self, path: Path):
+ """Sets the path or trajectory to track."""
+ if path == self.path_arg:
+ return
+ self.path_arg = path
+
+ # If the path has more than 2D, reduce to (x,y)
+ if len(path.points[0]) > 2:
+ path = path.get_dims([0,1])
+
+ # If no timing info, we can't rely on 'path'/'trajectory' speed
+ if not isinstance(path, Trajectory):
+ self.path = path.arc_length_parameterize()
+ self.trajectory = None
+ self.current_traj_parameter = 0.0
+ if self.desired_speed_source in ['path', 'trajectory']:
+ raise ValueError("Stanley: Provided path has no timing. Either provide a Trajectory or set a constant desired_speed.")
+ else:
+ self.path = path.arc_length_parameterize()
+ self.trajectory = path
+ self.current_traj_parameter = self.trajectory.domain()[0]
+
+ self.current_path_parameter = 0.0
+
+ def set_racing_path(self, path: Path):
+ if path == self.path_arg:
+ return
+ self.path_arg = path
+ if len(path.points[0]) > 2:
+ path = path.get_dims([0,1])
+ if not isinstance(path, Trajectory):
+ self.path = path.arc_length_parameterize()
+ self.trajectory = path.racing_velocity_profile()
+ self.current_traj_parameter = 0.0
+ if self.desired_speed_source not in ['racing']:
+ raise ValueError("Racing: desired speed must be set to racing, currently set to: " + str(self.desired_speed_source))
+ else:
+ self.path = path.arc_length_parameterize()
+ self.trajectory = path
+ self.current_traj_parameter = self.trajectory.domain()[0]
+ self.current_path_parameter = 0.0
+
+ def _find_front_axle_position(self, x, y, yaw):
+ """Compute front-axle world position from the center/rear and yaw."""
+ fx = x + self.wheelbase * cos(yaw)
+ fy = y + self.wheelbase * sin(yaw)
+ return fx, fy
+
+ def compute(self, state: VehicleState, component: Component = None):
+ """Compute the control outputs: (longitudinal acceleration, front wheel angle)."""
+ t = state.pose.t
+ if self.t_last is None:
+ self.t_last = t
+ dt = t - self.t_last
+
+
+
+ # Current vehicle states
+ curr_x = state.pose.x
+ curr_y = state.pose.y
+ curr_yaw = state.pose.yaw if state.pose.yaw is not None else 0.0
+ speed = state.v
+
+ if self.path is None:
+ if component:
+ component.debug_event("No path provided to Stanley controller. Doing nothing.")
+ return (0.0, 0.0)
+
+ # Ensure same frame
+ if self.path.frame != state.pose.frame:
+ if component:
+ component.debug_event(f"Transforming path from {self.path.frame.name} to {state.pose.frame.name}")
+ self.path = self.path.to_frame(state.pose.frame, current_pose=state.pose)
+
+ if self.trajectory and self.trajectory.frame != state.pose.frame:
+ if component:
+ component.debug_event(f"Transforming trajectory from {self.trajectory.frame.name} to {state.pose.frame.name}")
+ self.trajectory = self.trajectory.to_frame(state.pose.frame, current_pose=state.pose)
+
+ # 1) Closest point
+ fx, fy = self._find_front_axle_position(curr_x, curr_y, curr_yaw)
+ search_start = self.current_path_parameter - 5.0
+ search_end = self.current_path_parameter + 5.0
+ closest_dist, closest_parameter = self.path.closest_point_local((fx, fy), [search_start, search_end])
+ self.current_path_parameter = closest_parameter
+
+ # 2) Path heading
+ target_x, target_y = self.path.eval(closest_parameter)
+ index, u = self.path.time_to_index(closest_parameter)
+ tangent = self.path.eval_tangent(closest_parameter)
+ path_yaw = atan2(tangent[1], tangent[0])
+ desired_x = target_x
+ desired_y = target_y
+ # 3) Lateral error
+ dx = fx - target_x
+ dy = fy - target_y
+ left_vec = np.array([sin(curr_yaw), -cos(curr_yaw)])
+ cross_track_error = np.sign(np.dot(np.array([dx, dy]), left_vec)) * closest_dist
+
+ # 4) Heading error
+ yaw_error = normalise_angle(path_yaw - curr_yaw)
+
+ # 5) Standard Stanley terms
+ cross_term = atan2(self.k * cross_track_error, self.k_soft + speed)
+ desired_steering_angle = yaw_error + cross_term
+
+ desired_speed = self.desired_speed
+ feedforward_accel = 0.0
+ print(self.desired_speed)
+ # print(self.trajectory)
+ if self.trajectory and self.desired_speed_source in ['path', 'trajectory', 'racing']:
+ if len(self.trajectory.points) < 2 or self.current_path_parameter >= self.path.domain()[1]:
+ # End of trajectory -> stop
+ if component:
+ component.debug_event("Stanley: Past the end of trajectory, stopping.")
+ desired_speed = 0.0
+ feedforward_accel = -2.0
+ else:
+ # Use racing velocity profile as target
+ if self.desired_speed_source == 'racing':
+ # desired_speed = self.trajectory.velocity_variable(closest_parameter)
+ desired_speed = self.trajectory.velocities[index]
+ desired_speed = min(desired_speed, self.speed_limit)
+ # print("close param speed: " + str(closest_parameter))
+ # current_trajectory_time = self.trajectory.parameter_to_time(closest_parameter)
+ # print("time: " + str(current_trajectory_time))
+ # print("des x: " + str(desired_x))
+ # print("curr speed: " + str(speed))
+ # print("des speed: " + str(desired_speed))
+
+ # difference_dt = 0.1
+ # future_t = current_trajectory_time + difference_dt
+ # future_parameter = self.trajectory.time_to_parameter(future_t)
+ # next_desired_speed = self.trajectory.velocity_variable(future_parameter)
+ next_desired_speed = self.trajectory.velocities[index + 1]
+ next_desired_speed = min(next_desired_speed, self.speed_limit)
+ # print("next des speed: " + str(next_desired_speed))
+ difference_dt = self.trajectory.times[index + 1] - self.trajectory.times[index]
+ feedforward_accel = (next_desired_speed - desired_speed) / difference_dt
+ feedforward_accel = np.clip(feedforward_accel, -self.max_decel, self.max_accel)
+ if speed < next_desired_speed and feedforward_accel < 0:
+ feedforward_accel = 0.0
+ else:
+ if self.desired_speed_source == 'path':
+ current_trajectory_time = self.trajectory.parameter_to_time(self.current_path_parameter)
+ else:
+ self.current_traj_parameter += dt
+ current_trajectory_time = self.current_traj_parameter
+ print(current_trajectory_time)
+
+ deriv = self.trajectory.eval_derivative(current_trajectory_time)
+
+ # deriv 0 at time 0
+ if np.isnan(deriv[0]):
+ desired_speed = 0.0
+ else:
+ desired_speed = min(np.linalg.norm(deriv), self.speed_limit)
+
+ difference_dt = 0.1
+ future_t = current_trajectory_time + difference_dt
+ if future_t > self.trajectory.domain()[1]:
+ future_t = self.trajectory.domain()[1]
+ future_deriv = self.trajectory.eval_derivative(future_t)
+ next_desired_speed = min(np.linalg.norm(future_deriv), self.speed_limit)
+ feedforward_accel = (next_desired_speed - desired_speed) / difference_dt
+ feedforward_accel = np.clip(feedforward_accel, -self.max_decel, self.max_accel)
+ else:
+ if desired_speed is None:
+ desired_speed = 4.0
+
+ # Cross-track-based slowdown (less aggressive than before). More aggressive for racing
+ if self.desired_speed_source in ['racing']:
+ desired_speed *= np.exp(-abs(cross_track_error) * 1.5)
+ else:
+ desired_speed *= np.exp(-abs(cross_track_error) * 0.6)
+
+ # Clip to speed limit
+ if desired_speed > self.speed_limit:
+ desired_speed = self.speed_limit
+
+ # PID for longitudinal control
+ speed_error = desired_speed - speed
+ output_accel = self.pid_speed.advance(e=speed_error, t=t, feedforward_term=feedforward_accel)
+
+ # Clip acceleration
+ if output_accel > self.max_accel:
+ output_accel = self.max_accel
+ elif output_accel < -self.max_decel:
+ output_accel = -self.max_decel
+
+ # Avoid negative accel when fully stopped
+ if desired_speed == 0 and abs(speed) < 0.01 and output_accel < 0:
+ output_accel = 0.0
+
+ # Debug
+ if component is not None:
+ # component.debug("Stanley: fx, fy", (fx, fy))
+ component.debug('curr pt',(curr_x,curr_y))
+ component.debug("desired_x",desired_x)
+ component.debug("desired_y",desired_y)
+ component.debug("Stanley: path param", self.current_path_parameter)
+ component.debug("Stanley: crosstrack dist", closest_dist)
+ component.debug("crosstrack error", cross_track_error)
+ component.debug("Stanley: yaw_error", yaw_error)
+ component.debug('steering_angle', desired_steering_angle)
+ component.debug("Stanley: desired_speed (m/s)", desired_speed)
+ component.debug("Stanley: feedforward_accel (m/s^2)", feedforward_accel)
+ component.debug("Stanley: output_accel (m/s^2)", output_accel)
+ component.debug('Stanley: current yaw (rad)', curr_yaw)
+ component.debug('Stanley: current speed (m/s)', speed)
+
+
+ if output_accel > self.max_accel:
+ output_accel = self.max_accel
+
+ if output_accel < -self.max_decel:
+ output_accel = -self.max_decel
+
+ self.t_last = t
+ return (output_accel, desired_steering_angle)
+
+#####################################
+# 3. Tracker component
+#####################################
+class StanleyTrajectoryTracker(Component):
+ """
+ A trajectory-tracking Component that uses the above Stanley controller
+ for lateral control plus PID-based longitudinal control.
+ It now includes measures to mitigate oscillations.
+ """
+
+ def __init__(self, vehicle_interface=None, **kwargs):
+ """
+ :param vehicle_interface: The low-level interface to send commands to the vehicle.
+ :param kwargs: Optional parameters to pass into the Stanley(...) constructor.
+ """
+ self.stanley = Stanley(**kwargs)
+ self.vehicle_interface = vehicle_interface
+ self.desired_speed_source = settings.get('control.stanley.desired_speed', 'path')
+ self.stage_duration = settings.get('control.launch_control.stage_duration', 0.5)
+ self.enable_launch_control = settings.get('control.launch_control.enable', False) # and vehicle.v < 0.1
+
+ def rate(self):
+ """Control frequency in Hz."""
+ return 50.0
+
+ def state_inputs(self):
+ """
+ Required state inputs:
+ - Vehicle state
+ - Trajectory
+ """
+ return ["vehicle", "trajectory"]
+
+ def state_outputs(self):
+ """No direct output state here."""
+ return []
+
+ def update(self, vehicle: VehicleState, trajectory: Trajectory):
+ """
+ Per control cycle:
+ 1) Set the path/trajectory
+ 2) Compute (acceleration, front wheel angle)
+ 3) Convert front wheel angle to steering wheel angle (if necessary)
+ 4) Send command to the vehicle
+ """
+ # path to trajectory if racing enabled
+ # if self.desired_speed_source in ['racing']: ## conditional needed for no racing
+ # self.stanley.set_racing_path(trajectory)
+ # else:
+ # self.stanley.set_path(trajectory)
+ self.stanley.set_path(trajectory)
+ accel, f_delta = self.stanley.compute(vehicle, self)
+
+ # If your low-level interface expects steering wheel angle:
+ steering_angle = front2steer(f_delta)
+ steering_angle = np.clip(
+ steering_angle,
+ settings.get('vehicle.geometry.min_steering_angle', -0.5),
+ settings.get('vehicle.geometry.max_steering_angle', 0.5)
+ )
+
+ cmd = self.vehicle_interface.simple_command(accel, steering_angle, vehicle)
+
+ if self.enable_launch_control:
+ print("launch control active")
+ if not hasattr(self,'_launch_start_time'):
+ self._launch_start_time = rospy.get_time()
+ elapsed = rospy.get_time() - self._launch_start_time
+ if elapsed < self.stage_duration:
+ cmd.accelerator_pedal_position = 0.0
+ cmd.brake_pedal_position = 1.0
+ elif elapsed < 2 * self.stage_duration:
+ cmd.accelerator_pedal_position = 1.0
+ cmd.brake_pedal_position = 1.0
+ elif elapsed < 3 * self.stage_duration:
+ cmd.accelerator_pedal_position = 1.0
+ cmd.brake_pedal_position = 0.0
+ else:
+ self.enable_launch_control = False
+
+
+ self.vehicle_interface.send_command(cmd)
+
+ def healthy(self):
+ """Optional: check if the controller has a valid path."""
+ return self.stanley.path is not None
diff --git a/GEMstack/onboard/planning/velocity_profile.py b/GEMstack/onboard/planning/velocity_profile.py
new file mode 100644
index 000000000..2b13242fe
--- /dev/null
+++ b/GEMstack/onboard/planning/velocity_profile.py
@@ -0,0 +1,281 @@
+import numpy as np
+import sys
+import os
+import matplotlib.pyplot as plt
+from matplotlib.collections import LineCollection
+from scipy.signal import savgol_filter
+
+# from ..stanley import normalise_angle
+from ...knowledge.vehicle import dynamics
+from ...utils import settings
+
+# from ..mathutils import transforms,collisions
+
+
+def parse_route_csv(filename):
+ """
+ Parses the pure pursuit tracker log file and extracts the following data:
+ - vehicle time (from column index 19)
+ - X position actual (from column index 2)
+ - Y position actual (from column index 5)
+ - X position desired (from column index 11)
+ - Y position desired (from column index 14)
+ """
+
+ data = np.genfromtxt(filename, delimiter=',', skip_header=1)
+ x_desired = data[:, 0]
+ y_desired = data[:, 1]
+ return x_desired, y_desired
+
+def moving_average(data, window_size=9):
+ """
+ Simple moving average smoother for 1D array.
+ Pads edges by repeating border values.
+ """
+ pad = window_size // 2
+ padded = np.pad(data, (pad, pad), mode='edge')
+ smoothed = np.convolve(padded, np.ones(window_size) / window_size, mode='valid')
+ return smoothed
+
+def compute_curvature_by_distance(xs, ys, ds, spacing=2.0):
+ """
+ Computes curvature using 3-point method with approximately equal distance on both sides.
+ spacing: desired distance (in meters) from center point to side points.
+ """
+ xs = np.array(xs)
+ ys = np.array(ys)
+ N = len(xs)
+ kappa = np.zeros(N)
+
+ # Compute cumulative distances
+ s = np.insert(np.cumsum(ds), 0, 0)
+
+ for i in range(N):
+ # Find index j before i such that s[i] - s[j] ≈ spacing
+ j = i
+ while j > 0 and (s[i] - s[j]) < spacing:
+ j -= 1
+
+ # Find index k after i such that s[k] - s[i] ≈ spacing
+ k = i
+ while k < N - 1 and (s[k] - s[i]) < spacing:
+ k += 1
+
+ if j == i or k == i or j < 0 or k >= N:
+ kappa[i] = 0
+ continue
+
+ # Points: P1 (j), P2 (i), P3 (k)
+ x1, y1 = xs[j], ys[j]
+ x2, y2 = xs[i], ys[i]
+ x3, y3 = xs[k], ys[k]
+
+ # Triangle side lengths
+ a = np.hypot(x2 - x1, y2 - y1)
+ b = np.hypot(x3 - x2, y3 - y2)
+ c = np.hypot(x1 - x3, y1 - y3)
+ s_tri = (a + b + c) / 2
+
+ # Heron’s formula for area
+ area = np.sqrt(max(s_tri * (s_tri - a) * (s_tri - b) * (s_tri - c), 0))
+ denom = a * b * c
+
+ if area > 1e-6 and denom > 1e-6:
+ radius = (a * b * c) / (4 * area)
+ kappa[i] = 1 / radius
+ else:
+ kappa[i] = 0
+
+ kappa[np.abs(kappa) < 1e-2] = 0
+
+ return kappa
+
+def lateral_speed_limit(kappa, ay_max, v_max):
+ v_lat = np.sqrt(np.maximum(ay_max / (np.abs(kappa) + 1e-8), 0))
+ return np.minimum(v_lat, v_max)
+
+def limit_ax_for_friction_ellipse(v, kappa, ax_limit, ay_max):
+ # Compute a_y at current v
+ ay = v**2 * kappa
+ ay_ratio = ay / ay_max
+ # print(ay_ratio)
+ ay_ratio = np.clip(ay_ratio, -1.0, 1.0)
+ # Remaining fraction for ax
+ ax_ratio = np.sqrt(np.maximum(1.0 - ay_ratio**2, 0.0))
+ return ax_limit * ax_ratio
+
+def apply_trail_braking(ds, v_lat, kappa, ax_max, ax_min, ay_max, max_iter=2, tol=1e-3):
+ N = len(ds)
+ v_profile = v_lat.copy()
+ v_profile[0] = 0.0
+ forward_vs = v_lat.copy()
+ backward_vs = v_lat.copy()
+
+ for index, iteration in enumerate(range(max_iter)):
+ v_old = v_profile.copy()
+
+ # Forward (accelerating out of curves)
+ for i in range(1, N):
+ ax_limit = limit_ax_for_friction_ellipse(v_profile[i-1], kappa[i-1], ax_max, ay_max)
+ ax_limit = np.clip(ax_limit, ax_min, ax_max)
+ v_allowed = np.sqrt(v_profile[i-1]**2 + 2 * ax_limit * ds[i-1])
+ v_profile[i] = min(v_profile[i], v_allowed)
+ forward_vs[i] = v_allowed
+
+
+ # Backward (trail braking into corners)
+ for i in range(N - 1, 0, -1):
+ ax_limit = limit_ax_for_friction_ellipse(v_profile[i], kappa[i], abs(ax_min), ay_max)
+ arg = v_profile[i]**2 + 2 * ax_limit * ds[i]
+ v_allowed = np.sqrt(max(arg,0.0))
+ v_profile[i-1] = min(v_profile[i-1], v_allowed)
+
+ backward_vs[i-1] = v_allowed
+
+ # for i in range(N - 2, -1, -1):
+ # ax_limit = limit_ax_for_friction_ellipse(v_profile[i+1], kappa[i+1], abs(ax_min), ay_max)
+ # arg = v_profile[i+1]**2 + 2 * ax_limit * ds[i]
+ # # print("v_profile{i+1}: " + str(v_profile[i+1]))
+ # # print("ax_limit: " + str(ax_limit))
+ # # print("arg: " + str(arg))
+ # v_allowed = np.sqrt(max(arg,0.0))
+ # v_profile[i] = min(v_profile[i], v_allowed)
+
+ # # v_profile[i] = alpha * v_profile[i] + (1 - alpha) * v_allowed
+
+ # backward_vs[i] = v_allowed
+
+
+ # --- Check convergence ---
+ if np.allclose(v_profile, v_old, atol=tol):
+ print("converged in " + str(iteration) + " iterations")
+ break
+
+ return v_profile, forward_vs, backward_vs, v_lat
+
+def compute_time_profile(xs, ys, v_profile):
+ xs = np.array(xs)
+ ys = np.array(ys)
+ v_profile = np.array(v_profile)
+
+ dx = np.diff(xs)
+ dy = np.diff(ys)
+ ds = np.hypot(dx, dy) # segment distances
+
+ # Use average speed between points to estimate time between them
+ v_mid = (v_profile[:-1] + v_profile[1:]) / 2
+ v_mid = np.clip(v_mid, 0.1, None) # Avoid divide-by-zero
+
+ dt = ds / v_mid
+ t = np.insert(np.cumsum(dt), 0, 0.0) # cumulative time starting from 0
+
+ return t
+
+def plot_speed_profile_gradient(fig, axis, xs, ys, speeds, cmap='jet'):
+ xs = np.array(xs)
+ ys = np.array(ys)
+ speeds = np.array(speeds)
+
+ # Build segments between points
+ points = np.array([xs, ys]).T.reshape(-1, 1, 2)
+ segments = np.concatenate([points[:-1], points[1:]], axis=1)
+ # segments = [np.column_stack([xs, ysi]) for ysi in ys.T]
+
+ # Create line collection
+ lc = LineCollection(segments, cmap=cmap, linewidth=2)
+ lc.set_array(speeds[:-1]) # color values
+ lc.set_linewidth(2)
+
+ # fig, ax = plt.subplots(figsize=(8, 6))
+ line = axis.add_collection(lc)
+ fig.colorbar(line, ax=axis, label='Speed (m/s)')
+ axis.set_xlim(xs.min(), xs.max())
+ axis.set_ylim(ys.min(), ys.max())
+ axis.set_aspect('equal', adjustable='box')
+ axis.set_title('Speed Profile Along Path')
+ axis.set_xlabel('X [m]')
+ axis.set_ylabel('Y [m]')
+ plt.grid(True)
+
+def plot_x_y(axis, x, y, x_label, y_label):
+ axis.plot(x, y)#, label='Actual')
+ axis.set_xlabel(x_label)
+ axis.set_ylabel(y_label)
+ axis.grid(True)
+
+def compute_velocity_profile(points):
+
+ v_max = settings.get('vehicle.limits.max_speed')
+ ax_max = settings.get('vehicle.limits.max_longitudinal_acceleration')
+ ax_min = settings.get('vehicle.limits.min_longitudinal_acceleration')
+ ay_max = settings.get('vehicle.limits.max_lateral_acceleration')
+
+ points = np.array(points)
+ # print(points)
+ xs, ys = points[:,0], points [:,1]
+ # print(xs)
+
+ dx = np.diff(xs)
+ dy = np.diff(ys)
+ ds = np.hypot(dx, dy)
+ ds = np.append(ds, ds[-1])
+
+ kappa = compute_curvature_by_distance(xs,ys, ds)
+
+ v_lat = lateral_speed_limit(kappa, ay_max, v_max)
+ v_profile, forward_vs, backward_vs, v_lat = apply_trail_braking(ds, v_lat, kappa, ax_max, ax_min, ay_max)
+
+ v_profile = savgol_filter(v_profile, window_length=9, polyorder=3)
+
+ t = compute_time_profile(xs, ys, v_profile)
+
+ return t, v_profile
+
+
+
+if __name__=='__main__':
+ if len(sys.argv) != 2:
+ print("Usage: python velocity_profile.py ")
+ sys.exit(1)
+
+ path_file = sys.argv[1]
+
+ # if behavior.json doesn't exist, print error and exit
+ if not os.path.exists(path_file):
+ print("Error: route file not found.")
+ sys.exit(1)
+
+ xs, ys = parse_route_csv(path_file)
+
+ points = list(zip(xs,ys))
+
+ t, v_profile = compute_velocity_profile(points)
+
+ # # max long accel: 2.0769700074721493
+ # # min long accel: -2.6197231578072313
+ # # max lat accel: 3.3754426456004567
+
+ fig, axs = plt.subplots(2, 2, figsize=(12, 8))
+
+ dv = np.diff(v_profile)
+ dt = np.diff(t)
+
+ a = dv/dt
+
+ plot_x_y(axs[0, 0], t, v_profile, "t", "v")
+ plot_x_y(axs[0, 1], t[:-1], a, "t", "a")
+ # plot_x_y(axs[1, 0], xs, ys, "x", "y")
+ # plot_x_y(axs[1, 1], t, forward_vs, "t", "forward & backward vs")
+ # plot_x_y(axs[1, 1], t, backward_vs, "t", "forward & backward vs")
+ plot_x_y(axs[1, 1], t, xs, "t", "x & y")
+ plot_x_y(axs[1, 1], t, ys, "t", "x & y")
+ # plt.show()
+
+ plot_speed_profile_gradient(fig, axs[1, 0], xs, ys, v_profile)
+
+ plt.tight_layout()
+ plt.show()
+
+
+
+
diff --git a/GEMstack/scripts/__init__.py b/GEMstack/scripts/__init__.py
new file mode 100644
index 000000000..e69de29bb
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/agent.py b/GEMstack/state/agent.py
index 757805837..12149b937 100644
--- a/GEMstack/state/agent.py
+++ b/GEMstack/state/agent.py
@@ -11,6 +11,7 @@ class AgentEnum(Enum):
LARGE_TRUCK = 2
PEDESTRIAN = 3
BICYCLIST = 4
+ CONE = 5
class AgentActivityEnum(Enum):
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 d7a57db00..6e7232118 100644
--- a/GEMstack/state/trajectory.py
+++ b/GEMstack/state/trajectory.py
@@ -4,7 +4,11 @@
from ..mathutils import transforms,collisions
from .physical_object import ObjectFrameEnum, convert_point
import math
+import numpy as np
from typing import List,Tuple,Optional,Union
+from ..onboard.planning.velocity_profile import compute_velocity_profile
+from scipy.interpolate import splprep, splrep, splev
+
@dataclass
@register
@@ -79,6 +83,15 @@ def arc_length_parameterize(self, speed = 1.0) -> Trajectory:
times.append(times[-1] + d/speed)
return Trajectory(frame=self.frame,points=points,times=times)
+ def racing_velocity_profile(self) -> Trajectory:
+ """Returns a timed trajectory with max velocity profile parametrized by path radius"""
+ times = [0.0]
+ # print(self.points)
+ points = self.points
+ # print(points)
+ times, velocities = compute_velocity_profile(points)
+ return Trajectory(frame=self.frame,points=points,times=times, velocities=velocities)
+
def closest_point(self, x : List[float], edges = True) -> Tuple[float,float]:
"""Returns the closest point on the path to the given point. If
edges=False, only computes the distances to the vertices, not the
@@ -162,6 +175,99 @@ def trim(self, start : float, end : float) -> Path:
s = self.eval(start)
e = self.eval(end)
return replace(self,points=[s]+self.points[sind+1:eind]+[e])
+
+
+ def fit_curve_radius(self, vehicle_position: List[float], n_points: int) -> float:
+ """
+ Calculates the curve radius over the next 3 intervals and returns the largest.
+
+ Args:
+ vehicle_position: Current position of the vehicle [x, y, ...]
+ n_points: Number of points to sample ahead. Must be >= 5 to allow 3 intervals.
+
+ Returns:
+ float: Min radius among 3 consecutive 3-point intervals. Returns float('inf') if not enough data.
+ """
+ _, closest_point_idx_float = self.closest_point(vehicle_position)
+ closest_point_idx = int(math.ceil(closest_point_idx_float))
+
+ # Require at least 5 points to form 3 overlapping triplets
+ total_needed = max(n_points, 5)
+ end_idx = min(closest_point_idx + total_needed, len(self.points))
+
+ if end_idx - closest_point_idx < 5:
+ return float('0')
+
+ # Get the next chunk of points
+ points_to_check = self.points[closest_point_idx:end_idx]
+
+ # Convert to 2D
+ points_2d = [[p[0], p[1]] for p in points_to_check]
+
+ radii = []
+ for i in range(len(points_2d) - 2): # Slide a window of 3
+ triplet = points_2d[i:i+3]
+ try:
+ _, _, r = self._fit_circle_to_points(triplet)
+ radii.append(r)
+ except:
+ radii.append(float('inf')) # Treat failed fits as straight line
+
+ return min(radii) if radii else float('0')
+
+ def _fit_circle_to_points(self, points: List[List[float]]) -> Tuple[float, float, float]:
+ """
+ Approximates a circle from a set of 2D points using the circumcircle of the first three points.
+
+ Args:
+ points: List of [x, y] coordinates. Must contain at least 3 points.
+
+ Returns:
+ Tuple[float, float, float]: Center coordinates (h, k) and radius r
+ """
+ if len(points) < 3:
+ raise ValueError("At least 3 points are required to fit a circle")
+
+ p1, p2, p3 = points[0], points[1], points[2]
+
+ # Build matrices for determinant calculation
+ def det(matrix):
+ return np.linalg.det(np.array(matrix))
+
+ A = [
+ [p1[0], p1[1], 1],
+ [p2[0], p2[1], 1],
+ [p3[0], p3[1], 1]
+ ]
+ D = det(A)
+ if abs(D) < 1e-10:
+ raise ValueError("Points are collinear or nearly collinear")
+
+ a = p1[0]**2 + p1[1]**2
+ b = p2[0]**2 + p2[1]**2
+ c = p3[0]**2 + p3[1]**2
+
+ M11 = [
+ [a, p1[1], 1],
+ [b, p2[1], 1],
+ [c, p3[1], 1]
+ ]
+ M12 = [
+ [a, p1[0], 1],
+ [b, p2[0], 1],
+ [c, p3[0], 1]
+ ]
+ M13 = [
+ [a, p1[0], p1[1]],
+ [b, p2[0], p2[1]],
+ [c, p3[0], p3[1]]
+ ]
+
+ h = 0.5 * det(M11) / D
+ k = -0.5 * det(M12) / D
+ r = math.sqrt(h**2 + k**2 + det(M13) / D)
+
+ return h, k, r
@dataclass
@@ -169,6 +275,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"""
@@ -285,7 +392,25 @@ def compute_headings(path : Path, smoothed = False) -> Path:
estimate good tangent vectors.
"""
if smoothed:
- raise NotImplementedError("Smoothing not done yet")
+ # raise NotImplementedError("Smoothing not done yet")
+ points = np.array(path.points)
+ x = points[:, 0]
+ y = points[:, 1]
+
+ dx = np.diff(x)
+ dy = np.diff(y)
+ ds = np.hypot(dx, dy)
+ s = np.insert(np.cumsum(ds), 0, 0)
+
+ tck_x = splrep(s, x, s=0.5)
+ tck_y = splrep(s, y, s=0.5)
+
+ s_fine = np.linspace(0, s[-1], 200)
+ x_smooth = splev(s_fine, tck_x)
+ y_smooth = splev(s_fine, tck_y)
+
+ path.points = np.vstack((x_smooth, y_smooth)).T
+
if len(path.points) < 2:
raise ValueError("Path must have at least 2 points")
derivs = []
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/generate_circle.py b/GEMstack/utils/generate_circle.py
new file mode 100644
index 000000000..bc09cf195
--- /dev/null
+++ b/GEMstack/utils/generate_circle.py
@@ -0,0 +1,19 @@
+import numpy as np
+import pandas as pd
+
+# Parameters
+radius = 20 # radius of the circle in meters
+num_points = 100 # number of points around the circle
+
+# Generate angles from 0 to 2π
+angles = np.linspace(0, 2 * np.pi, num_points, endpoint=False)
+
+# Compute x and y coordinates
+x = radius * np.cos(angles)
+y = radius * np.sin(angles)
+
+# Create a DataFrame
+circle_df = pd.DataFrame({'x': x, 'y': y})
+
+# Save to CSV
+circle_df.to_csv('circle_points.csv', index=False)
\ No newline at end of file
diff --git a/GEMstack/utils/generate_figure8.py b/GEMstack/utils/generate_figure8.py
new file mode 100644
index 000000000..d93d778f5
--- /dev/null
+++ b/GEMstack/utils/generate_figure8.py
@@ -0,0 +1,28 @@
+import numpy as np
+import pandas as pd
+
+# Parameters
+radius_left = 10 # Radius scaling on the left side
+radius_right = 20 # Radius scaling on the right side
+num_points = 200 # Total number of points
+rotation_angle_deg = -45 # Rotation angle in degrees
+
+# Convert degrees to radians
+theta = np.radians(rotation_angle_deg)
+
+# Generate parametric figure-8 (lemniscate-style)
+t = np.linspace(-np.pi/2, 3*np.pi/2, num_points)
+x = np.sin(t)
+y = np.sin(t) * np.cos(t)
+
+# Apply asymmetric scaling
+x_scaled = np.where(x < 0, x * radius_left, x * radius_right)
+y_scaled = np.where(x < 0, y * radius_left, y * radius_right)
+
+# Apply rotation
+x_rotated = x_scaled * np.cos(theta) - y_scaled * np.sin(theta)
+y_rotated = x_scaled * np.sin(theta) + y_scaled * np.cos(theta)
+
+# Create DataFrame and save
+figure8_df = pd.DataFrame({'x': x_rotated, 'y': y_rotated})
+figure8_df.to_csv('../GEMstack/GEMstack/knowledge/routes/figure8.csv', index=False)
\ No newline at end of file
diff --git a/GEMstack/utils/klampt_visualization.py b/GEMstack/utils/klampt_visualization.py
index 063f690c7..6347b33c2 100644
--- a/GEMstack/utils/klampt_visualization.py
+++ b/GEMstack/utils/klampt_visualization.py
@@ -16,6 +16,7 @@
AgentEnum.BICYCLIST : (0,0,1,1),
AgentEnum.MEDIUM_TRUCK : (1,0,1,1),
AgentEnum.LARGE_TRUCK : (0,1,1,1),
+ AgentEnum.CONE : (0,1,0,1),
None: (0.7,0.7,0.7,1),
}
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/HOMEWORK.md b/HOMEWORK.md
new file mode 100644
index 000000000..e5bbe7b9d
--- /dev/null
+++ b/HOMEWORK.md
@@ -0,0 +1,194 @@
+# CS 588 Phase 1 Homework
+
+Due date: 2/24
+
+**Overall objective**: work together in large teams to create a nontrivial integrated behavior on the vehicle. The target behavior will be to drive along a predefined track, and slowing down for pedestrians that would otherwise be hit if the vehicle continues at normal speed. The vehicle should stop when necessary.
+
+**Skills**: Familiarization with GEMstack repo, Git branches and pull requests, lab and equipment logistics, inter-team communication.
+
+**On-board development**: If you are working on the GEM vehicle, your work will go into the `cs588_groupX/` folder. We recommend that before you start, you
+a) Ensure that your GEMstack repository is on the correct branch. cd into `cs588_groupX/GEMstack` and run `git status`. It should show that you are on the `s2025_groupX` branch.
+b) Get the latest updates to the course stack. To do so, run `git pull` and `git merge s2025`.
+
+When you are done, commit your development of this component and launch files to your group's branch. **DO NOT** set the global git authentication on the vehicle to your account. The easiest way to do this is:
+a) Log onto Github under your account name. [Create a Github Personal Access Token](https://docs.github.com/en/authentication/keeping-your-account-and-data-secure/managing-your-personal-access-tokens#creating-a-personal-access-token-classic). To reduce the chance of mischief, choose the "Only select repositories" option and set the access token just to push to this repository. Open the "Repository permissions" and change the "Contents" access to "Read and write"
+b) When your token is generated, copy the token and keep it somewhere safe.
+c) Commit your changes to your branch.
+d) Run "git push". In "Username" put your Github username, and in "Password" use the token that you copied in step b). This should now be reflected in your branch.
+
+When you are creating a pull request to the `s2025_teamX` branch of GEMstack, you can do this through the Github webpage. You can also use the hub command line tool: https://hub.github.com/. Ensure that this shows up in the `s2025_teamX` branch's Pull Requests tab.
+
+**Quality-of-life tips**
+- By default, the log folder is shown after each run. If this is annoying, change the launch file to read `after: show_log_folder: False`.
+- Each component can generate CSV files that collect fast streaming data for later analysis. Use `self.debug(item,value)` or `self.debug_event(label)` in your component's initialize(), update(), or cleanup() functions. These will be stored in LOG_FOLDER/COMPONENT_debug.csv.
+- Find all magic constants in your code. Move them into the `GEMstack/knowledge/defaults/current.yaml` file under appropriate sub-keys.
+
+
+**To submit**: ensure your group's work is merged into the `s2025_teamA` or `s2025_teamB` branches (as appropriate) with appropriately logged PRs. We will review your team's branch history. Your group will submit some evidence of its component working, and if successful your team will submit an integrated video of the behavior working. These may be posted to Slack or Clickup.
+
+
+## Group Leads
+
+- Decide on a good day of the week and time for group meetings.
+- Discuss and decide on Github pull request procedures for your team's branches.
+- Discuss and decide on project management and communication features for your team (e.g., Slack / Clickup).
+- Lead your group and team with clear expectations to prepare work in time for integration. Don't leave this to the last minute! Suggest establishing an internal deadline of 2/17 for all technical pieces.
+- Keep track of team members' efforts, especially if their contributions are not apparent through branch commit history. At the end of this phase you will be reporting on your members' contributions, so if they are not listed in PRs and you have little to say about their work, they will receive low individual scores for this assignment. Note that they will be reporting on your leadership as well, so remember to treat your group fairly.
+- Gather sufficient evidence (e.g., videos of partial system tests or simulation tests, or a report with text and figures) that your group has succeeded in its objectives.
+- Decide which group on your team will test the integrated behavior. Have them report results, and capture a video of successful runs.
+
+
+## Control & Dynamics Group
+- Starter code is provided in the `homework/` folder in your group's branch.
+- All members must complete safety lookout training; at least two must complete safety driver training.
+
+Part 1:
+
+1. Flash a distress signal to the vehicle via ROS. Modify the `blink.py` program to print messages from some of the "/pacmod/parsed_tx/X" topics (at least 2). For each topic, you will need to create a ROS subscriber. Read the documentation on https://github.com/astuff/pacmod2 to figure out which message types to use and extract printable data from these messages.
+
+ Now, create a publisher for the "/pacmod/as_rx/turn_cmd" topic. You will then flash a "distress signal" corresponding to left turn signal for 2 seconds, right turn signal for 2s, and then turn signals off for 2s. This will then repeat forever until you press Ctrl+C.
+
+ To run your code on the vehicle, you will launch the sensors and drive-by-wire system, then enable Pacmod control via the joystick. (Please do not try to operate the vehicle with the joystick!) Then, run your program with `python3 blink.py`. After you are done, you should disable Pacmod control via the joystick.
+
+2. Adapt `blink.py` to run the behavior in the GEMstack executor. Copy blink_launch.yaml to `GEMstack/launch`. Copy `blink_component.py` to `GEMstack/onboard/planning/` and make your edits there.
+
+ Replicate your sensor printing and distress signal code in the BlinkDistress class in blink_component.py. You will need to adapt your code from using ROS subscribers / publishers to using the `GEMVehicleInterface` and `GEMVehicleReading` objects provided in the template code. Opening the GEMstack folder in the VSCode IDE will help you find the documentation for these classes.
+
+ Run your code in simulation first. (If you are running on the vehicle, first open one terminal window and run `roscore`. Keep this running.) Then, in the GEMstack folder, run `python3 main.py --variant=sim launch/blink_launch.yaml`. You should see your blinking sequence in a 3D visualization window. Use Ctrl+C to quit.
+
+ Now, run your code on the real vehicle. Enable Pacmod control as before, then run `python3 main.py launch/blink_launch.yaml`.
+
+3. Adapt your code so the distress signal runs on GEMstack as a `signaling` component, and blinks the distress signal only when the `AllState.intent.intent=HALTING` flag is set. You will need to modify the computation graph in `GEMstack/knowledge/defaults` to add the `signaling` component, and modify launch files so your class is no longer listed under `trajectory_tracking`.
+4. Use Git to create a pull request, and have your PR approved to the `s2025_teamX` branch.
+
+Part 2:
+1. Tune the low-level controller (currently `PurePursuit`) to track the trajectory `AllState.trajectory` produced by the Planning group as accurately as possible. You may tune steering, acceleration/braking, the tracking strategies, or all three.
+2. Decide on an appropriate tracking quality metric with the Infra team.
+3. Report on what you tuned and how the tracking accuracy metric was improved.
+4. Move all magic constants to an appropriate settings file, and have your pull request approved.
+5. Integrate as necessary.
+
+
+## State estimation & Calibration Group
+
+- Have at least one team member complete safety lookout & driver training.
+
+Part 1:
+
+1. You will be using both the Oak RGB-D camera and the Ouster top lidar to estimate the 3D positions of pedestrians relative to the vehicle frame. Because the stereo depth estimate is not as accurate as the lidar, we will be using the image to detect objects and the lidar to measure their 3D extent. The first step of this process is to associate points in the camera with points in the lidar, which requires an understanding of projection and relative pose (extrinsics) calibration.
+2. You will first need to capture a calibration dataset consisting of paired images and lidar scans. Write code to capture paired scans and take several snapshots of interesting scenes. You should save images as standard image files, and save lidar scans as numpy arrays or PCD files. Store these to a directory named GEMstack/data/SOMETHING where "SOMETHING" is a descriptive name of your dataset. In the main GEMstack folder we had a GEM e2 program `python3 GEMstack/offboard/calibration/capture_lidar_zed.py data/SOMETHING` that could capture these files. Create a similar program `capture_ouster_oak.py` that reads from the appropriate ROS topics.
+3. Use the `CameraInfo` message to obtain the intrinsics of the camera (http://docs.ros.org/en/noetic/api/sensor_msgs/html/msg/CameraInfo.html) from the `/oak/rgb/camera_info` ROS topic. You may use the image_geometry module (https://docs.ros.org/en/api/image_geometry/html/python/) to project points in the camera frame to the image. A camera frame is defined with the z axis pointing forward, x pointing right, and y pointing down. The important values of this message are the fx, fy, cx ,and cy intrinsic parameter terms. You can store these values to disk or read them live in your code.
+4. We do not have the relative transform `T_toplidar^frontcamera` that converts points from the top lidar (Ouster) frame to the Oak frame. Create a way to calibrate this transform. Specifically, if you have a dataset of paired image, point cloud pairs `(image^t,point_cloud^t)`, you should observe that the points belonging to some object in the point cloud are mapped directly to those pixels in the image. Specifically, if `image_pt` is an image pixel belonging to point pt in the point cloud, then we should observe the relation "image_pt = project(T_toplidar^frontcamera * pt, oak_intrinsics)"
+
+ To obtain this matrix you may use manual calibration if you need to, or you could use a more sophisticated method.
+
+ For manual calibration, you can modify the GEM e2 code `python3 GEMstack/offboard/calibration/klampt_show_lidar_zed.py data/SOMETHING` to visualize the stored point clouds from the front camera and the lidar. You can see why the forward depth estimates are quite poor.
+
+ Automated methods could use a detection method to obtain a distinctive shape like a sphere or a square (e.g., a face of the foam cubes) in the Zed image, paired with the same shape in the lidar point cloud. An optimization would ensure that all lidar points belonging to the shape are projected to its projection in the image. You can also match the stereo and lidar point clouds using a dynamically-associated registration method like ICP.
+
+
+Part 2:
+
+1. Now we will perform absolute calibration of vehicle height, rear axle center, and sensors, i.e., the vehicle frame. The vehicle frame is centered at the rear axle center, with x pointing forward, y pointing to the left, and z pointing up. We want the transforms `T_frontcamera^vehicle` and `T_toplidar^vehicle`.
+
+ - A flat ground and walls are good references for the pitch/roll of the sensors. Using the lidar point cloud, calibrate the rotation component of this transform. Also, use the height of the ground to determine the z above ground.
+ - Using distinctive shapes (e.g., the foam cubes), create a dataset in which you set up objects on the centerline of the vehicle. Use these to calibrate the yaw and the horizontal offset of the lidar.
+ - Measure the height of the rear axle over the ground. Use this to figure out the z above the rear axle center.
+
+2. Combine all of these measurements to establish `T_toplidar^vehicle`. Use your result in Step 1 to compute `T_frontcamera^vehicle` as well. Store these calibrations into the files referenced by `GEMstack/knowledge/calibration/gem_e4.yaml`. Name your calibrations meaningfully -- specifying which vehicle and what type of calibration you are performing -- and include the time and data of the calibration in your files.
+3. Put your offline calibration code in the `GEMstack/offboard/calibration/` directory and write a README with a description of the method that you used, and instructions about how to use it. Describe the results of your calibration steps 1 and 2 in this file.
+
+ DO NOT commit data files used in calibration. Put your datasets in the `data` directory, named appropriately. Files in this directory will not be committed to the repo.
+
+4. Use Git to create a pull request to the `s2025_teamX` branch, and have your PR approved.
+5. Integrate as necessary.
+
+
+## Perception Group
+
+- Starter code is provided in the `homework/` folder in your group's branch.
+- Have at least one team member complete safety lookout & driver training.
+- Many of your team members should plan to work on the vehicle, at least in the early stages of the assignment. Plan to coordinate with the Infra team to enable a method for working offline.
+
+Part 1:
+1. Use an object detector to identify a pedestrian from the front camera. Implement the function `detect_people(img)` in `person_detector.py` to return a list of bounding boxes of people in an image. This is a function that inputs OpenCV images and returns a list of (x,y,w,h) image boxes that contain people. To run it, call `person_detector.py IMAGE` where IMAGE is an image file. You may download images from the internet or take your own. If you have a webcam, you can run `person_detector.py webcam` to run the live detector.
+
+ I suggest using the YOLOv8 package (https://github.com/ultralytics/ultralytics) and choosing one of its pretrained models, such as `yolov8n.pt`. Follow the basic tutorials for running the detector. The ID of people is 0, and you can examine the Result object to extract out the boxes that have that ID.
+2. Refactor your detector to work with GEMstack. Move your detector logic into a GEMstack Component defined in `pedestrian_detection.py`. The provided code will turn your boxes into a dictionary of `AgentState` objects. Read the documentation of the `AgentState` class to see what data should be stored there. For now, you will put temporary values for most of these fields.
+
+ Specifically you should:
+
+ 1. Implement the `PedestrianDetector2D` component to call your detection function in `image_callback(img)`. Your model should be loaded once in the component's `initialize()` method.
+ 2. Move your pretrained model to `GEMstack/knowledge/detection`.
+ 3. Move the Python code to `GEMstack/onboard/perception` where the launch file can find them.
+ 4. Make sure that your code can find the pretrained model in the `knowledge` directory.
+ 5. Using the detector-only variant of the launch file `python3 main.py --variant=detector_only pedestrian_detection.yaml`, test your code on the real vehicle. You will need to run "source ~/demo_ws/devel/setup.bash" and "roslaunch basic_launch sensor_init.launch" in another terminal, and run the same "source ..." command before running GEMstack code.
+ 6. Have a group member(s) walk in front of the Zed camera and observe the printouts.
+ 7. Finally, tune the rate at which you run your component to obtain the highest framerate possible.
+
+3. Use Git to create a pull request to `s2025_teamX`, and have your PR approved.
+
+Part 2:
+1. Fuse detections with depth (`front_depth` sensor), multiple cameras, and/or LIDAR (`top_lidar` sensor) to reduce errors and place agents in their 3D locations in the scene. Use the sensor calibration from the Calibration group. Look at the lidar readings near the center of the detection, and use those to estimate a region of interest in the point cloud. Then, fit the center and dimensions of the object to the points in the point cloud that you associate with the pedestrian. Finally, put the estimated center and dimensions of the pedestrian into the "pose" and "dimensions" attributes, making sure to respect the vehicle's coordinate convention.
+2. If the Infra team has worked quickly enough, you should be able to work offline, replaying from ROS bags. It is a good idea to coordinate with them.
+3. Provide your results in a `PedestrianDetector` component and provide this to the Planning group.
+
+Part 3:
+1. Keep track of `AgentState` objects as the vehicle moves and when they disappear out of the field of view.
+2. Track pedestrians over time to fill out the "velocity" attribute and to give them relatively consistent names over time.
+ - number pedestrian IDs as "ped1", "ped2", etc. so that if you detect that a single pedestrian has moved across your field of view, you consistently output "ped1" as the agent's ID.
+ - keep track of the detected pedestrians on the prior frame to estimate the velocity of each pedestrian. Make sure to store 3D previous detections in the START frame. For each current detection, examine whether the box of the new detection overlaps any prior detection. If so, this begins a "track" detection in which you a) keep the last ID, and b) estimate the pedestrian's velocity in the CURRENT frame. The reported velocity should NOT be relative to the vehicle's velocity. If this is a new pedestrian, increment the pedestrian ID and output zero velocity for this frame.
+
+ If you wish to use more sophisticated trackers, e.g., Hungarian algorithm, velocity prediction, etc, you may do so.
+
+3. Make sure this works while the vehicle is moving. For example, if the pedestrian is staying still but the vehicle is moving, their reported velocity remains relatively close to 0. Provide these results to the Planning group.
+4. Integrate as necessary.
+
+
+## Planning Group
+
+- Have at least one team member complete safety lookout & driver training.
+
+Part 1:
+1. We will introduce two new components that operate on the output of a `PedestrianDetector2D` / `PedestrianDetector` model produced by the perception team:
+
+ - Logic in the `PedestrianYielder` component in `pedestrian_yield_logic.py`.
+ - A planner in the `YieldTrajectoryPlanner` component in `longitudinal_planning.py`.
+
+ Move these files to `GEMstack/onboard/planning` where launch files can find them.
+
+3. For the planning logic, you will implement a braking strategy in `longitudinal_plan_brake()`, and implement a trapezoidal velocity profile strategy in `longitudinal_plan()`.
+
+ You will first do your development using a unit test script, then in simulation. Run `test_longitudinal_planning.py` from the main GEMstack folder to plot the results of your methods. Using the launch file `python3 main.py --variant=fake_sim pedestrian_detection.yaml`, you will receive perfect knowledge about the pedestrian. Test to make sure this produces reasonable behavior in the simulation. It should slow and stop at a safe distance when a pedestrian is detected, and then resume slowly when the pedestrian disappears.
+4. Run on the vehicle using `--variant fake_real`. This will use a "fake" detector that will just report pedestrians at some point. Work with the Control and Dynamics team to ensure that reasonable behavior results.
+5. Use Git to create a pull request, and have your PR approved.
+
+Part 2:
+1. Use collision detection to determine the distance to collision and use that to determine whether to begin to brake.
+
+ - Determine the lookahead distance that you would need to avoid collision at the current velocity and desired braking deceleration.
+ - For many steps along the route up to that distance, determine whether the vehicle would be likely to hit (more precisely, get sufficiently close) to the pedestrian. Use a 1m lateral distance and 3m longitudinal distance buffer in your vehicle geometry.
+ - For the distance-to-collision you determine above, use the longitudinal planner to determine your desired acceleration.
+
+ Determine how quickly you can run your planner. If it is too slow (<5Hz), try using the vehicle-pedestrian distance to dynamically determine your collision checking resolution.
+
+2. Modify the `PedestrianYielder` so that it selects a subset of pedestrians for which the above calculations should be performed.
+3. Adapt the motion planner to slow gently for distant crossing pedestrians to boost rate of progress after the pedestrian crosses the vehicle's route. Use the Perception group's estimated velocity for each pedestrian.
+4. Using the `--variant real_real` will run on the real vehicle using trajectory predictions from the Perception group.
+5. Integrate as necessary.
+
+
+## Infra Group
+- Have at least one team member complete safety lookout & driver training.
+
+Part 1:
+1. Develop a systematic method for saving camera data for the Calibration and Vision groups. Work closely with them to figure out a method to test their methods from logged data.
+2. Write documentation for this method, detailing usage and performance issues.
+3. Use Git to create a pull request to `s2025_teamX`, and have your PR approved.
+
+Part 2:
+1. Develop a visualizer for rapidly plotting detected pedestrian trajectories from log data (e.g., matplotlib).
+2. Work with the Control & Dynamics team to test the integrated system.
+3. Develop metrics for pedestrian safety and passenger comfort. Analyze logs from tests.
+4. Integrate as necessary.
+
diff --git a/README.md b/README.md
index 51f26e290..b7d69edd7 100644
--- a/README.md
+++ b/README.md
@@ -11,25 +11,124 @@
GEMstack uses Python 3.7+ and ROS Noetic. (It is possible to do some offline and simulation work without ROS, but it is highly recommended to install it if you are working on any onboard behavior or training for rosbag files.)
You should also have the following Python dependencies installed, which you can install from this folder using `pip install -r requirements.txt`:
-
-- numpy
-- scipy
-- matplotlib
-- opencv-python
-- torch
-- klampt
-- shapely
-- dacite
-- pyyaml
+- GEMstack Dependencies
+ - numpy
+ - scipy
+ - matplotlib
+ - opencv-python
+ - torch
+ - klampt==0.9.2
+ - shapely
+ - dacite
+ - pyyaml
+- Perception Dependencies
+ - ultralytics
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.
-From a fresh Ubuntu 20.04 with ROS Noetic and [CUDA 11.6 installed](https://gist.github.com/ksopyla/bf74e8ce2683460d8de6e0dc389fc7f5), you can install these dependencies by running `setup/setup_this_machine.sh` from the top-level GEMstack folder.
+## 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.
+
+## Prerequisites
+- Docker (In Linux - Make sure to follow the post-installation steps from [here](https://docs.docker.com/engine/install/linux-postinstall/))
+- Nvidia Container Toolkit
+
+Try running the sample workload from the [NVIDIA Container Toolkit](https://docs.nvidia.com/datacenter/cloud-native/container-toolkit/latest/sample-workload.html) to check if your system is compatible.
-To build a Docker container with all these prerequisites, you can use the provided Dockerfile by running `docker build -t gem_stack setup/`. For GPU support you will need the NVidia Container Runtime (run `setup/get_nvidia_container.sh` from this directory to install, or see [this tutorial](https://collabnix.com/introducing-new-docker-cli-api-support-for-nvidia-gpus-under-docker-engine-19-03-0-beta-release/) to install) and run `docker run -it --gpus all gem_stack /bin/bash`.
+```bash
+sudo docker run --rm --runtime=nvidia --gpus all ubuntu nvidia-smi
+```
+You should see the nvidia-smi output similar to [this](https://docs.nvidia.com/datacenter/cloud-native/container-toolkit/latest/sample-workload.html#:~:text=all%20ubuntu%20nvidia%2Dsmi-,Your%20output%20should%20resemble%20the%20following%20output%3A,-%2B%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2D%2B%0A%7C%20NVIDIA%2DSMI%20535.86.10).
+
+If you see the output, you are good to go. Otherwise, you will need to install the Docker and NVidia Container Toolkit by following the instructions.
+- For **Docker**, follow the instructions [here](https://docs.docker.com/engine/install/ubuntu/#install-using-the-repository).
+
+- 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.
+
+```bash
+bash setup/build_docker_image.sh
+```
+
+## Running the Docker container
+
+To run the container, you can use the provided Docker Compose file by running.
+> [!NOTE]
+> If you want to open multiple terminals to run the container, you can use the same command. It will automatically start a new terminal inside the same container.
+```bash
+bash run_docker_container.sh
+```
+## Usage Tips and Instructions
+
+### Using Host Volume
+
+You can use the host volume under the container's home directory inside the `` folder. This allows you to build and run files that are on the host machine. For example, if you have a file on the host machine at `/home//project`, you can access it inside the container at `/home//host/project`.
+
+### Using Dev Containers Extension in VSCode
+
+To have a good developer environment inside the Docker container, you can use the Dev Containers extension in VSCode. Follow these steps:
+
+1. Install the Dev Containers extension in VSCode.
+2. Open the cloned repository in VSCode.
+3. Press `ctrl+shift+p`(or select the remote explorer icon from the left bar) and select `Dev-Containers: Attach to Running Container...`.
+4. Select the container name `gem_stack-container`.
+5. Once attached, Select `File->Open Folder...`.
+6. Select the folder/workspace you want to open in the container.
+
+This will set up the development environment inside the Docker container, allowing you to use VSCode features seamlessly.
+
+## Stopping the Docker container
+
+To stop the container, you can use the provided stop script by running.
+
+```bash
+bash stop_docker_container.sh
+```
## In this folder
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/homework/blink.py b/homework/blink.py
new file mode 100644
index 000000000..b83d3c49c
--- /dev/null
+++ b/homework/blink.py
@@ -0,0 +1,130 @@
+import rospy
+from std_msgs.msg import String, Bool, Float32, Float64
+from pacmod_msgs.msg import PositionWithSpeed, PacmodCmd, SystemRptInt, SystemRptFloat, VehicleSpeedRpt
+
+TURN_RIGHT = 0
+TURN_NONE = 1
+TURN_LEFT = 2
+TURN_HAZARD = 3
+# For message format, see
+# https://github.com/astuff/astuff_sensor_msgs/blob/3.3.0/pacmod_msgs/msg/PacmodCmd.msg
+
+class BlinkDistress:
+ """Your control loop code should go here. You will use ROS and Pacmod messages
+ to communicate with drive-by-wire system to control the vehicle's turn signals.
+ """
+ def __init__(self):
+ # TODO: Initialize your publishers and subscribers here
+
+ # When you create a subscriber to a /pacmod/parsed_tx/X topic, you will need to provide a callback function.
+ # You will want this callback to be a BlinkDistress method, such as print_X(self, msg). msg will have a
+ # ROS message type, and you can find out what this is by either reading the documentation or running
+ # "rostopic info /pacmod/parsed_tx/X" on the command line.
+ # check update file good
+
+ self.turn_blink_pub = rospy.Publisher('/pacmod/as_rx/turn_cmd', PacmodCmd, queue_size=1)
+ # Define blink cmd
+ self.turn_cmd = PacmodCmd()
+
+ # Subscribers to /pacmod/parsed_tx/X (at least 2)
+ self.speed_sub = rospy.Subscriber("/pacmod/parsed_tx/vehicle_speed_rpt", VehicleSpeedRpt, self.speed_callback)
+ self.accel_sub = rospy.Subscriber("/pacmod/parsed_tx/accel_rpt", SystemRptFloat, self.accel_callback)
+
+ pass
+
+ def rate(self):
+ """Requested update frequency, in Hz"""
+ return 0.5
+
+ def initialize(self):
+ """Run first"""
+ pass
+
+ def cleanup(self):
+ """Run last"""
+ pass
+
+ def get_dir_distress(self):
+ pass
+
+ def update(self):
+ """Run in a loop"""
+ # TODO: Implement your control loop here
+ # You will need to publish a PacmodCmd() to /pacmod/as_rx/turn_cmd. Read the documentation to see
+ # what the data in the message indicates.
+ #self.turn_cmd = PacmodCmd()
+ # TODO change to actual direction in Part 2
+
+ if self.turn_cmd.ui16_cmd == TURN_NONE:
+ self.turn_cmd.ui16_cmd = TURN_LEFT
+ elif self.turn_cmd.ui16_cmd == TURN_LEFT:
+ self.turn_cmd.ui16_cmd = TURN_RIGHT
+ else:
+ self.turn_cmd.ui16_cmd = TURN_NONE
+ self.turn_blink_pub.publish(self.turn_cmd)
+
+ pass
+
+ def healthy(self):
+ """Returns True if the element is in a stable state."""
+ return True
+
+ def done(self):
+ """Return True if you want to exit."""
+ return False
+
+ def speed_callback(self, msg):
+ """Callback for /pacmod/parsed_tx/vehicle_speed_rpt"""
+ rospy.loginfo(f"Vehicle Speed: {msg.vehicle_speed} m/s | Valid: {msg.vehicle_speed_valid}")
+
+ def accel_callback(self, msg):
+ """Callback for /pacmod/parsed_tx/accel_rpt"""
+ rospy.loginfo("--- Acceleration Report ---")
+ rospy.loginfo(f"Header Timestamp: {msg.header.stamp.to_sec()}")
+
+ # Boolean status flags
+ rospy.loginfo(f"Enabled: {msg.enabled}")
+ rospy.loginfo(f"Override Active: {msg.override_active}")
+ rospy.loginfo(f"Command Output Fault: {msg.command_output_fault}")
+ rospy.loginfo(f"Input Output Fault: {msg.input_output_fault}")
+ rospy.loginfo(f"Output Reported Fault: {msg.output_reported_fault}")
+ rospy.loginfo(f"PACMod Fault: {msg.pacmod_fault}")
+ rospy.loginfo(f"Vehicle Fault: {msg.vehicle_fault}")
+
+ # Float values
+ rospy.loginfo(f"Manual Input: {msg.manual_input} (Driver Input)")
+ rospy.loginfo(f"Command: {msg.command} (Requested Acceleration)")
+ rospy.loginfo(f"Output: {msg.output} (Final Output to Vehicle)")
+ rospy.loginfo("---------------------------\n")
+
+def run_ros_loop(node, Allstate):
+ """Executes the event loop of a node using ROS. `node` should support
+ rate(), initialize(), cleanup(), update(), and done(). You should not modify
+ this code.
+ """
+ #intializes the node. We use disable_signals so that the end() function can be called when Ctrl+C is issued.
+ #See http://wiki.ros.org/rospy/Overview/Initialization%20and%20Shutdown
+ rospy.init_node(node.__class__.__name__, disable_signals=True)
+
+ node.initialize()
+ rate = rospy.Rate(node.rate())
+ termination_reason = "undetermined"
+ try:
+ while not rospy.is_shutdown() and not node.done() and node.healthy():
+ node.update(node, Allstate)
+ rate.sleep()
+ if node.done():
+ termination_reason = "Node done"
+ if not node.healthy():
+ termination_reason = "Node in unhealthy state"
+ except KeyboardInterrupt:
+ termination_reason = "Killed by user"
+ except Exception as e:
+ termination_reason = "Exception "+str(e)
+ raise
+ finally:
+ node.cleanup()
+ rospy.signal_shutdown(termination_reason)
+
+if __name__ == '__main__':
+ run_ros_loop(BlinkDistress())
\ No newline at end of file
diff --git a/homework/blink_component.py b/homework/blink_component.py
new file mode 100644
index 000000000..18fb41c6b
--- /dev/null
+++ b/homework/blink_component.py
@@ -0,0 +1,39 @@
+from ..component import Component
+from ..interface.gem import GEMInterface,GEMVehicleCommand,GEMVehicleReading
+
+
+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
+
+ def rate(self):
+ """Requested update frequency, in Hz"""
+ return 0.5
+
+ def initialize(self):
+ """Run first"""
+ pass
+
+ def cleanup(self):
+ """Run last"""
+ pass
+
+ def update(self):
+ """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.
+ 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 healthy(self):
+ """Returns True if the element is in a stable state."""
+ return True
+
diff --git a/homework/longitudinal_planning.py b/homework/longitudinal_planning.py
new file mode 100644
index 000000000..c3f3bf737
--- /dev/null
+++ b/homework/longitudinal_planning.py
@@ -0,0 +1,93 @@
+from typing import List
+from ..component import Component
+from ...state import AllState, VehicleState, EntityRelation, EntityRelationEnum, Path, Trajectory, Route, ObjectFrameEnum
+from ...utils import serialization
+from ...mathutils.transforms import vector_madd
+
+def longitudinal_plan(path : Path, acceleration : float, deceleration : float, max_speed : float, current_speed : float) -> Trajectory:
+ """Generates a longitudinal trajectory for a path with a
+ trapezoidal velocity profile.
+
+ 1. accelerates from current speed toward max speed
+ 2. travel along max speed
+ 3. if at any point you can't brake before hitting the end of the path,
+ decelerate with accel = -deceleration until velocity goes to 0.
+ """
+ path_normalized = path.arc_length_parameterize()
+ #TODO: actually do something to points and times
+ points = [p for p in path_normalized.points]
+ times = [t for t in path_normalized.times]
+ trajectory = Trajectory(path.frame,points,times)
+ return trajectory
+
+
+def longitudinal_brake(path : Path, deceleration : float, current_speed : float) -> Trajectory:
+ """Generates a longitudinal trajectory for braking along a path."""
+ path_normalized = path.arc_length_parameterize()
+ #TODO: actually do something to points and times
+ points = [p for p in path_normalized.points]
+ times = [t for t in path_normalized.times]
+ trajectory = Trajectory(path.frame,points,times)
+ return trajectory
+
+
+class YieldTrajectoryPlanner(Component):
+ """Follows the given route. Brakes if you have to yield or
+ you are at the end of the route, otherwise accelerates to
+ the desired speed.
+ """
+ def __init__(self):
+ self.route_progress = None
+ self.t_last = None
+ self.acceleration = 0.5
+ self.desired_speed = 1.0
+ self.deceleration = 2.0
+
+ def state_inputs(self):
+ return ['all']
+
+ def state_outputs(self) -> List[str]:
+ return ['trajectory']
+
+ def rate(self):
+ return 10.0
+
+ def update(self, state : AllState):
+ vehicle = state.vehicle # type: VehicleState
+ route = state.route # type: Route
+ t = state.t
+
+ if self.t_last is None:
+ self.t_last = t
+ dt = t - self.t_last
+
+ curr_x = vehicle.pose.x
+ curr_y = vehicle.pose.y
+ curr_v = vehicle.v
+
+ #figure out where we are on the route
+ if self.route_progress is None:
+ self.route_progress = 0.0
+ closest_dist,closest_parameter = state.route.closest_point_local((curr_x,curr_y),[self.route_progress-5.0,self.route_progress+5.0])
+ self.route_progress = closest_parameter
+
+ #extract out a 10m segment of the route
+ route_with_lookahead = route.trim(closest_parameter,closest_parameter+10.0)
+
+ #parse the relations indicated
+ should_brake = False
+ for r in state.relations:
+ if r.type == EntityRelationEnum.YIELD and r.obj1 == '':
+ #yielding to something, brake
+ should_brake = True
+ should_accelerate = (not should_brake and curr_v < self.desired_speed)
+
+ #choose whether to accelerate, brake, or keep at current velocity
+ if should_accelerate:
+ traj = longitudinal_plan(route_with_lookahead, self.acceleration, self.deceleration, self.desired_speed, curr_v)
+ elif should_brake:
+ traj = longitudinal_brake(route_with_lookahead, self.deceleration, curr_v)
+ else:
+ traj = longitudinal_plan(route_with_lookahead, 0.0, self.deceleration, self.desired_speed, curr_v)
+
+ return traj
diff --git a/homework/pedestrian_detection.py b/homework/pedestrian_detection.py
new file mode 100644
index 000000000..3134b1e35
--- /dev/null
+++ b/homework/pedestrian_detection.py
@@ -0,0 +1,84 @@
+from ...state import AllState,VehicleState,ObjectPose,ObjectFrameEnum,AgentState,AgentEnum,AgentActivityEnum
+from ..interface.gem import GEMInterface
+from ..component import Component
+#from ultralytics import YOLO
+#import cv2
+from typing import Dict
+
+def box_to_fake_agent(box):
+ """Creates a fake agent state from an (x,y,w,h) bounding box.
+
+ The location and size are pretty much meaningless since this is just giving a 2D location.
+ """
+ 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)
+
+
+class PedestrianDetector2D(Component):
+ """Detects pedestrians."""
+ def __init__(self,vehicle_interface : GEMInterface):
+ self.vehicle_interface = vehicle_interface
+ #self.detector = YOLO('../../knowledge/detection/yolov8n.pt')
+ self.last_person_boxes = []
+
+ def rate(self):
+ return 4.0
+
+ def state_inputs(self):
+ return ['vehicle']
+
+ def state_outputs(self):
+ return ['agents']
+
+ def initialize(self):
+ #tell the vehicle to use image_callback whenever 'front_camera' gets a reading, and it expects images of type cv2.Mat
+ #self.vehicle_interface.subscribe_sensor('front_camera',self.image_callback,cv2.Mat)
+ pass
+
+ #def image_callback(self, image : cv2.Mat):
+ # detection_result = self.detector(image)
+ # self.last_person_boxes = []
+ # #uncomment if you want to debug the detector...
+ # #for bb in self.last_person_boxes:
+ # # 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.imwrite("pedestrian_detections.png",image)
+
+ def update(self, vehicle : VehicleState) -> Dict[str,AgentState]:
+ res = {}
+ for i,b in enumerate(self.last_person_boxes):
+ x,y,w,h = b
+ res['pedestrian'+str(i)] = box_to_fake_agent(b)
+ if len(res) > 0:
+ print("Detected",len(res),"pedestrians")
+ return res
+
+
+class FakePedestrianDetector2D(Component):
+ """Triggers a pedestrian detection at some random time ranges"""
+ 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 times in self.times:
+ if t >= times[0] and t <= times[1]:
+ res['pedestrian0'] = box_to_fake_agent((0,0,0,0))
+ print("Detected a pedestrian")
+ return res
diff --git a/homework/pedestrian_detection.yaml b/homework/pedestrian_detection.yaml
new file mode 100644
index 000000000..0fffa89fc
--- /dev/null
+++ b/homework/pedestrian_detection.yaml
@@ -0,0 +1,97 @@
+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 : pedestrian_detection.PedestrianDetector2D
+ perception_normalization : StandardPerceptionNormalizer
+ planning:
+ relations_estimation: pedestrian_yield_logic.PedestrianYielder
+ 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
+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
+
+
+ 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:
+ state_estimation : OmniscientStateEstimator
diff --git a/homework/pedestrian_yield_logic.py b/homework/pedestrian_yield_logic.py
new file mode 100644
index 000000000..2567c0093
--- /dev/null
+++ b/homework/pedestrian_yield_logic.py
@@ -0,0 +1,22 @@
+from ...state import AgentState,AgentEnum,EntityRelation,EntityRelationEnum
+from ..component import Component
+from typing import List,Dict
+
+class PedestrianYielder(Component):
+ """Yields for all pedestrians in the scene.
+
+ Result is stored in the relations graph.
+ """
+ def rate(self):
+ return None
+ def state_inputs(self):
+ return ['agents']
+ def state_outputs(self):
+ return ['relations']
+ def update(self,agents : Dict[str,AgentState]) -> List[EntityRelation]:
+ res = []
+ for n,a in agents.items():
+ if a.type == AgentEnum.PEDESTRIAN:
+ #relation: ego-vehicle yields to pedestrian
+ res.append(EntityRelation(type=EntityRelationEnum.YIELDING,obj1='',obj2=n))
+ return res
diff --git a/homework/person_detector.py b/homework/person_detector.py
new file mode 100644
index 000000000..8f4fa3588
--- /dev/null
+++ b/homework/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/homework/test_longitudinal_plan.py b/homework/test_longitudinal_plan.py
new file mode 100644
index 000000000..400f34fea
--- /dev/null
+++ b/homework/test_longitudinal_plan.py
@@ -0,0 +1,80 @@
+#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
+
+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()
+
+ 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()
+
+ test_traj = longitudinal_plan(test_path, 1.0, 2.0, 3.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("Accelerating from 0 m/s")
+ plt.xlabel('time')
+ plt.ylabel('position')
+ plt.show()
+
+
+ test_traj = longitudinal_plan(test_path, 1.0, 2.0, 3.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("Accelerating from 2 m/s")
+ plt.xlabel('time')
+ plt.ylabel('position')
+ plt.show()
+
+ test_traj = longitudinal_plan(test_path, 0.0, 2.0, 3.0, 3.1)
+ 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()
+
+ test_traj = longitudinal_plan(test_path, 2.0, 2.0, 20.0, 10.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("Too little time to stop, starting at 10 m/s")
+ plt.xlabel('time')
+ plt.ylabel('position')
+ 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()
+
+ test_traj = longitudinal_plan(test_path2, 1.0, 2.0, 3.0, 0.0)
+ 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()
+
+
+
+if __name__ == '__main__':
+ test_longitudinal_planning()
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/dash_fixed_route.yaml b/launch/dash_fixed_route.yaml
new file mode 100644
index 000000000..09bf44c48
--- /dev/null
+++ b/launch/dash_fixed_route.yaml
@@ -0,0 +1,81 @@
+description: "Drive the GEM vehicle along a fixed route (currently xyhead_highbay_backlot_p.csv)"
+mode: hardware
+vehicle_interface: gem_hardware.GEMHardwareInterface
+mission_execution: StandardExecutor
+# Recovery behavior after a component failure
+recovery:
+ planning:
+ trajectory_tracking:
+ type: recovery.StopTrajectoryTracker
+ print: False
+# Driving behavior for the GEM vehicle following a fixed route
+drive:
+ perception:
+ state_estimation : GNSSStateEstimator
+ perception_normalization : StandardPerceptionNormalizer
+ planning:
+ route_planning:
+ type: StaticRoutePlanner
+ args: [!relative_path '../GEMstack/knowledge/routes/forward_50m.csv']
+ motion_planning:
+ type: RouteToTrajectoryPlanner
+ args: [null] #desired speed in m/s. If null, this will keep the route untimed for the trajectory tracker
+ trajectory_tracking:
+ type: pure_pursuit.PurePursuitTrajectoryTracker
+ args: {desired_speed: 2.5} #approximately 5mph
+ 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','trajectory_tracking']
+ # 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:
+ # For replaying sensor data, try !include "../knowledge/defaults/standard_sensor_ros_topics.yaml"
+ ros_topics : []
+ components : []
+
+#usually can keep this constant
+computation_graph: !include "../GEMstack/knowledge/defaults/computation_graph.yaml"
+
+after:
+ show_log_folder: True #set to false to avoid showing the log folder
+
+#on load, variants will overload the settings structure
+variants:
+ #sim variant doesn't execute on the real vehicle
+ #real variant executes on the real robot
+ sim:
+ run:
+ mode: simulation
+ vehicle_interface:
+ type: gem_simulator.GEMDoubleIntegratorSimulationInterface
+ args:
+ scene: !relative_path '../scenes/xyhead_demo.yaml'
+
+ drive:
+ perception:
+ state_estimation : OmniscientStateEstimator
+ agent_detection : OmniscientAgentDetector
+ visualization: !include "klampt_visualization.yaml"
+ #visualization: !include "mpl_visualization.yaml"
+ log_ros:
+ log:
+ ros_topics : !include "../GEMstack/knowledge/defaults/standard_ros_topics.yaml"
\ No newline at end of file
diff --git a/launch/fixed_route.yaml b/launch/fixed_route.yaml
index c05de8ff7..af3e62199 100644
--- a/launch/fixed_route.yaml
+++ b/launch/fixed_route.yaml
@@ -16,14 +16,16 @@ drive:
planning:
route_planning:
type: StaticRoutePlanner
- args: [!relative_path '../GEMstack/knowledge/routes/xyhead_highbay_backlot_p.csv']
+ args: [!relative_path '../GEMstack/knowledge/routes/xyhead_highbay_backlot_oval.csv']
motion_planning:
type: RouteToTrajectoryPlanner
args: [null] #desired speed in m/s. If null, this will keep the route untimed for the trajectory tracker
trajectory_tracking:
- type: pure_pursuit.PurePursuitTrajectoryTracker
- args: {desired_speed: 2.5} #approximately 5mph
- print: False
+ #type: pure_pursuit.PurePursuitTrajectoryTracker # to use pure pursuit comment below
+ type: stanley.StanleyTrajectoryTracker # to use stanley comment above
+ # args: {desired_speed: 10} #approximately 5mph comment when racing
+ print: True
+
log:
# Specify the top-level folder to save the log files. Default is 'logs'
#folder : 'logs'
@@ -43,6 +45,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:
@@ -76,4 +80,4 @@ variants:
#visualization: !include "mpl_visualization.yaml"
log_ros:
log:
- ros_topics : !include "../GEMstack/knowledge/defaults/standard_ros_topics.yaml"
\ No newline at end of file
+ ros_topics : !include "../GEMstack/knowledge/defaults/standard_ros_topics.yaml"
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..4b59cc3a3
--- /dev/null
+++ b/launch/pedestrian_detection.yaml
@@ -0,0 +1,119 @@
+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 : pedestrian_detection.PedestrianDetector2D
+ 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/planner_sim.yaml b/launch/planner_sim.yaml
new file mode 100644
index 000000000..7eebe7d90
--- /dev/null
+++ b/launch/planner_sim.yaml
@@ -0,0 +1,83 @@
+description: "Drive the GEM vehicle along a fixed route (currently xyhead_highbay_backlot_p.csv)"
+mode: hardware
+vehicle_interface: gem_hardware.GEMHardwareInterface
+mission_execution: StandardExecutor
+# Recovery behavior after a component failure
+recovery:
+ planning:
+ trajectory_tracking:
+ type: recovery.StopTrajectoryTracker
+ print: False
+# Driving behavior for the GEM vehicle following a fixed route
+drive:
+ perception:
+ state_estimation : GNSSStateEstimator
+ perception_normalization : StandardPerceptionNormalizer
+ planning:
+ route_planning:
+ type: StaticRoutePlanner
+ args: [!relative_path '../GEMstack/knowledge/routes/racing_circle.csv'] # [Option] slalom.csv / racing_circle.csv
+ motion_planning:
+ type: racing_planning.SlalomTrajectoryPlanner
+ # args: [null] #desired speed in m/s. If null, this will keep the route untimed for the trajectory tracker
+ trajectory_tracking:
+ type: pure_pursuit.PurePursuitTrajectoryTracker # to use pure pursuit comment below
+ # type: stanley.StanleyTrajectoryTracker # to use stanley comment above
+ args: {desired_speed: 10} #approximately 5mph
+ print: True
+
+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','trajectory_tracking']
+ # 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:
+ # For replaying sensor data, try !include "../knowledge/defaults/standard_sensor_ros_topics.yaml"
+ ros_topics : []
+ components : []
+
+#usually can keep this constant
+computation_graph: !include "../GEMstack/knowledge/defaults/computation_graph.yaml"
+
+after:
+ show_log_folder: True #set to false to avoid showing the log folder
+
+#on load, variants will overload the settings structure
+variants:
+ #sim variant doesn't execute on the real vehicle
+ #real variant executes on the real robot
+ sim:
+ run:
+ mode: simulation
+ vehicle_interface:
+ type: gem_simulator.GEMDoubleIntegratorSimulationInterface
+ args:
+ scene: !relative_path '../scenes/racing_sim_circle.yaml' # [Option] racing_sim_slalom.yaml / racing_sim_circle.yaml
+
+ drive:
+ perception:
+ state_estimation : OmniscientStateEstimator
+ agent_detection : OmniscientAgentDetector
+ visualization: !include "klampt_visualization.yaml"
+ #visualization: !include "mpl_visualization.yaml"
+ log_ros:
+ log:
+ ros_topics : !include "../GEMstack/knowledge/defaults/standard_ros_topics.yaml"
diff --git a/launch/racing_fixed_slalom.yaml b/launch/racing_fixed_slalom.yaml
new file mode 100644
index 000000000..2b40d51d2
--- /dev/null
+++ b/launch/racing_fixed_slalom.yaml
@@ -0,0 +1,82 @@
+description: "Drive the GEM vehicle along a fixed route (currently xyhead_highbay_backlot_p.csv)"
+mode: hardware
+vehicle_interface: gem_hardware.GEMHardwareInterface
+mission_execution: StandardExecutor
+# Recovery behavior after a component failure
+recovery:
+ planning:
+ trajectory_tracking:
+ type: recovery.StopTrajectoryTracker
+ print: False
+# Driving behavior for the GEM vehicle following a fixed route
+drive:
+ perception:
+ state_estimation : GNSSStateEstimator
+ perception_normalization : StandardPerceptionNormalizer
+ planning:
+ route_planning:
+ type: StaticRoutePlanner
+ args: [!relative_path '../GEMstack/knowledge/routes/turn_right2.csv']
+ motion_planning:
+ type: racing_planning.SlalomTrajectoryPlanner
+ trajectory_tracking:
+ #type: pure_pursuit.PurePursuitTrajectoryTracker # to use pure pursuit comment below
+ type: stanley.StanleyTrajectoryTracker # to use stanley comment above
+ args: {desired_speed: 10} #approximately 5mph
+ print: True
+
+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','trajectory_tracking']
+ # 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:
+ # For replaying sensor data, try !include "../knowledge/defaults/standard_sensor_ros_topics.yaml"
+ ros_topics : []
+ components : []
+
+#usually can keep this constant
+computation_graph: !include "../GEMstack/knowledge/defaults/computation_graph.yaml"
+
+after:
+ show_log_folder: True #set to false to avoid showing the log folder
+
+#on load, variants will overload the settings structure
+variants:
+ #sim variant doesn't execute on the real vehicle
+ #real variant executes on the real robot
+ sim:
+ run:
+ mode: simulation
+ vehicle_interface:
+ type: gem_simulator.GEMDoubleIntegratorSimulationInterface
+ args:
+ scene: !relative_path '../scenes/racing_sim_slalom.yaml'
+
+ drive:
+ perception:
+ state_estimation : OmniscientStateEstimator
+ agent_detection : OmniscientAgentDetector
+ visualization: !include "klampt_visualization.yaml"
+ #visualization: !include "mpl_visualization.yaml"
+ log_ros:
+ log:
+ ros_topics : !include "../GEMstack/knowledge/defaults/standard_ros_topics.yaml"
diff --git a/launch/racing_fixed_slalom_online.yaml b/launch/racing_fixed_slalom_online.yaml
new file mode 100644
index 000000000..0f92e056d
--- /dev/null
+++ b/launch/racing_fixed_slalom_online.yaml
@@ -0,0 +1,82 @@
+description: "Drive the GEM vehicle along a fixed route (currently xyhead_highbay_backlot_p.csv)"
+mode: hardware
+vehicle_interface: gem_hardware.GEMHardwareInterface
+mission_execution: StandardExecutor
+# Recovery behavior after a component failure
+recovery:
+ planning:
+ trajectory_tracking:
+ type: recovery.StopTrajectoryTracker
+ print: False
+# Driving behavior for the GEM vehicle following a fixed route
+drive:
+ perception:
+ state_estimation : GNSSStateEstimator
+ perception_normalization : StandardPerceptionNormalizer
+ planning:
+ route_planning:
+ type: StaticRoutePlanner
+ args: [!relative_path '../GEMstack/knowledge/routes/turn_right2.csv']
+ motion_planning:
+ type: racing_planning_online.SlalomTrajectoryPlanner
+ trajectory_tracking:
+ #type: pure_pursuit.PurePursuitTrajectoryTracker # to use pure pursuit comment below
+ type: stanley.StanleyTrajectoryTracker # to use stanley comment above
+ args: {desired_speed: 10} #approximately 5mph
+ print: True
+
+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','trajectory_tracking']
+ # 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:
+ # For replaying sensor data, try !include "../knowledge/defaults/standard_sensor_ros_topics.yaml"
+ ros_topics : []
+ components : []
+
+#usually can keep this constant
+computation_graph: !include "../GEMstack/knowledge/defaults/computation_graph.yaml"
+
+after:
+ show_log_folder: True #set to false to avoid showing the log folder
+
+#on load, variants will overload the settings structure
+variants:
+ #sim variant doesn't execute on the real vehicle
+ #real variant executes on the real robot
+ sim:
+ run:
+ mode: simulation
+ vehicle_interface:
+ type: gem_simulator.GEMDoubleIntegratorSimulationInterface
+ args:
+ scene: !relative_path '../scenes/racing_sim_slalom.yaml'
+
+ drive:
+ perception:
+ state_estimation : OmniscientStateEstimator
+ agent_detection : OmniscientAgentDetector
+ visualization: !include "klampt_visualization.yaml"
+ #visualization: !include "mpl_visualization.yaml"
+ log_ros:
+ log:
+ ros_topics : !include "../GEMstack/knowledge/defaults/standard_ros_topics.yaml"
diff --git a/requirements.txt b/requirements.txt
index 94db8ba43..58a232ad5 100644
--- a/requirements.txt
+++ b/requirements.txt
@@ -4,6 +4,11 @@ scipy
matplotlib
torch
shapely
-klampt
+klampt==0.9.2
pyyaml
dacite
+
+# Perception
+ultralytics
+open3d
+sklearn
diff --git a/run_docker_container.sh b/run_docker_container.sh
new file mode 100644
index 000000000..c987a9016
--- /dev/null
+++ b/run_docker_container.sh
@@ -0,0 +1,8 @@
+#!/bin/bash
+# Check if container is already running
+if [ "$(docker ps -q -f name=gem_stack-container)" ]; then
+ docker exec -it gem_stack-container bash
+else
+ docker compose -f setup/docker-compose.yaml up -d
+ docker exec -it gem_stack-container bash
+fi
\ No newline at end of file
diff --git a/scenes/racing_sim_circle.yaml b/scenes/racing_sim_circle.yaml
new file mode 100644
index 000000000..b64345db5
--- /dev/null
+++ b/scenes/racing_sim_circle.yaml
@@ -0,0 +1,34 @@
+# vehicle_state: [-5.0, 20.0, 1.6, 0.0, 0.0] # [x, y, yaw, v, front_wheel_angle]
+vehicle_state: [0.0, 0.0, 0.0, 0.0, 0.0] # [x, y, yaw, v, front_wheel_angle]
+agents:
+ cone1:
+ type: pedestrian
+ position: [0.0, 70.0]
+ nominal_velocity: 0.0
+ target: [0.0, 70.0]
+ # target: [10.0,10.0]
+ behavior: loop
+
+ cone2:
+ type: pedestrian
+ position: [30.0, 70.0]
+ nominal_velocity: 0.0
+ target: [30.0, 70.0]
+ # target: [10.0,10.0]
+ behavior: loop
+
+ cone3:
+ type: pedestrian
+ position: [30.0, 0.0]
+ nominal_velocity: 0.0
+ target: [30.0, 0.0]
+ # target: [10.0,10.0]
+ behavior: loop
+
+ cone4:
+ type: pedestrian
+ position: [0.0, 0.0]
+ nominal_velocity: 0.0
+ target: [0.0, 0.0]
+ # target: [10.0,10.0]
+ behavior: loop
diff --git a/scenes/racing_sim_slalom.yaml b/scenes/racing_sim_slalom.yaml
new file mode 100644
index 000000000..6065b0dbb
--- /dev/null
+++ b/scenes/racing_sim_slalom.yaml
@@ -0,0 +1,33 @@
+vehicle_state: [0.0, 0.0, 0.0, 0.0, 0.0] # [x, y, yaw, v, front_wheel_angle]
+agents:
+ cone1:
+ type: cone
+ position: [10.0, 0.0]
+ nominal_velocity: 0.0
+ target: [10.0, 0.0]
+ # target: [10.0,10.0]
+ behavior: stationary
+
+ cone2:
+ type: cone
+ position: [30.0, 1.0]
+ nominal_velocity: 0.0
+ target: [30.0, 1.0]
+ # target: [10.0,10.0]
+ behavior: stationary
+
+ cone3:
+ type: cone
+ position: [50.0, 0.0]
+ nominal_velocity: 0.0
+ target: [50.0, 0.0]
+ # target: [10.0,10.0]
+ behavior: stationary
+
+ cone4:
+ type: cone
+ position: [70.0, 1.0]
+ nominal_velocity: 0.0
+ target: [70.0, 1.0]
+ # target: [10.0,10.0]
+ behavior: stationary
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 b/setup/Dockerfile.cuda11.8
similarity index 54%
rename from setup/Dockerfile
rename to setup/Dockerfile.cuda11.8
index b35c3b85d..8c299bf15 100644
--- a/setup/Dockerfile
+++ b/setup/Dockerfile.cuda11.8
@@ -1,7 +1,28 @@
FROM nvidia/cuda:11.8.0-cudnn8-devel-ubuntu20.04
+
+ARG USER_UID=1000
+ARG USER_GID=1000
+ARG USER=$(whoami)
+
+ENV DEBIAN_FRONTEND=noninteractive
+
#use bash instead of sh
-RUN rm /bin/sh && ln -s /bin/bash /bin/sh
+SHELL ["/bin/bash", "-c"]
+
RUN apt-get update && apt-get install -y git python3 python3-pip wget zstd
+
+# 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 Zed SDK
+RUN wget https://download.stereolabs.com/zedsdk/4.0/cu118/ubuntu20 -O zed_sdk.run
+RUN chmod +x zed_sdk.run
+RUN ./zed_sdk.run -- silent
+
# 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'
@@ -13,19 +34,18 @@ RUN apt-get install -y python3-rosdep python3-rosinstall python3-rosinstall-gene
RUN rosdep init
RUN rosdep update
-#Install Cuda 11.8
-#RUN wget https://developer.download.nvidia.com/compute/cuda/repos/ubuntu2004/x86_64/cuda-ubuntu2004.pin
-#RUN sudo mv cuda-ubuntu2004.pin /etc/apt/preferences.d/cuda-repository-pin-600
-##add public keys
-#RUN sudo apt-key adv --fetch-keys https://developer.download.nvidia.com/compute/cuda/repos/ubuntu2004/x86_64/3bf863cc.pub
-#RUN sudo add-apt-repository "deb http://developer.download.nvidia.com/compute/cuda/repos/ubuntu2004/x86_64/ /"
-#RUN install cuda-toolkit-11-8
+ARG USER
+ARG USER_UID
+ARG USER_GID
+# Create user more safely
+RUN groupadd -g ${USER_GID} ${USER} || groupmod -n ${USER} $(getent group ${USER_GID} | cut -d: -f1)
+RUN useradd -l -m -u ${USER_UID} -g ${USER_GID} ${USER} || usermod -l ${USER} -m -u ${USER_UID} -g ${USER_GID} $(getent passwd ${USER_UID} | cut -d: -f1)
+RUN echo "${USER} ALL=(ALL) NOPASSWD:ALL" >> /etc/sudoers
-# install Zed SDK
-RUN wget https://download.stereolabs.com/zedsdk/4.0/cu118/ubuntu20 -O zed_sdk.run
-RUN chmod +x zed_sdk.run
-RUN ./zed_sdk.run -- silent
+# 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 ROS Catkin workspace
RUN mkdir -p /catkin_ws/src
@@ -42,8 +62,23 @@ RUN cd /catkin_ws/src && git clone https://github.com/ros-perception/radar_msgs.
RUN source /opt/ros/noetic/setup.bash && cd /catkin_ws && rosdep install --from-paths src --ignore-src -r -y
RUN source /opt/ros/noetic/setup.bash && cd /catkin_ws && catkin_make -DCMAKE_BUILD_TYPE=Release
-# install GEMstack Python dependencies
-RUN git clone https://github.com/krishauser/GEMstack.git
-RUN cd GEMstack && pip3 install -r requirements.txt
+# Copy requirements.txt from host (now relative to parent directory)
+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
+
+USER ${USER}
+
+# Add ROS and GEMstack paths to bashrc
+RUN echo "source /opt/ros/noetic/setup.bash" >> /home/${USER}/.bashrc
+RUN echo "source /catkin_ws/devel/setup.bash" >> /home/${USER}/.bashrc
+
+# BASE END CONFIG
+WORKDIR /home/${USER}
-RUN echo /catkin_ws/devel/setup.sh
+ENTRYPOINT ["/bin/bash"]
\ No newline at end of file
diff --git a/setup/Dockerfile.cuda12 b/setup/Dockerfile.cuda12
new file mode 100644
index 000000000..81e2c262e
--- /dev/null
+++ b/setup/Dockerfile.cuda12
@@ -0,0 +1,84 @@
+FROM nvidia/cuda:12.0.0-cudnn8-devel-ubuntu20.04
+
+ARG USER_UID=1000
+ARG USER_GID=1000
+ARG USER=$(whoami)
+
+ENV DEBIAN_FRONTEND=noninteractive
+
+#use bash instead of sh
+SHELL ["/bin/bash", "-c"]
+
+RUN apt-get update && apt-get install -y git python3 python3-pip wget zstd
+
+# 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 Zed SDK
+RUN wget https://stereolabs.sfo2.cdn.digitaloceanspaces.com/zedsdk/4.2/ZED_SDK_Ubuntu20_cuda12.1_v4.2.4.zstd.run -O zed_sdk.run
+RUN chmod +x zed_sdk.run
+RUN ./zed_sdk.run -- silent
+
+# 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
+RUN rosdep init
+RUN rosdep update
+
+ARG USER
+ARG USER_UID
+ARG USER_GID
+
+# Create user more safely
+RUN groupadd -g ${USER_GID} ${USER} || groupmod -n ${USER} $(getent group ${USER_GID} | cut -d: -f1)
+RUN useradd -l -m -u ${USER_UID} -g ${USER_GID} ${USER} || usermod -l ${USER} -m -u ${USER_UID} -g ${USER_GID} $(getent passwd ${USER_UID} | cut -d: -f1)
+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 ROS Catkin workspace
+RUN mkdir -p /catkin_ws/src
+
+# install ROS dependencies and packages
+RUN cd /catkin_ws/src && git clone https://github.com/krishauser/POLARIS_GEM_e2.git
+RUN cd /catkin_ws/src && git clone --recurse-submodules https://github.com/stereolabs/zed-ros-wrapper.git
+RUN cd /catkin_ws/src && git clone https://github.com/astuff/pacmod2.git
+ #for some reason the ibeo messages don't work?
+RUN cd /catkin_ws/src && git clone https://github.com/astuff/astuff_sensor_msgs.git && rm -rf astuff_sensor_msgs/ibeo_msgs
+RUN cd /catkin_ws/src && git clone https://github.com/ros-perception/radar_msgs.git \
+ && cd radar_msgs && git checkout noetic
+
+RUN source /opt/ros/noetic/setup.bash && cd /catkin_ws && rosdep install --from-paths src --ignore-src -r -y
+RUN source /opt/ros/noetic/setup.bash && cd /catkin_ws && catkin_make -DCMAKE_BUILD_TYPE=Release
+
+# Copy requirements.txt from host (now relative to parent directory)
+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
+
+USER ${USER}
+
+# Add ROS and GEMstack paths to bashrc
+RUN echo "source /opt/ros/noetic/setup.bash" >> /home/${USER}/.bashrc
+RUN echo "source /catkin_ws/devel/setup.bash" >> /home/${USER}/.bashrc
+
+# BASE END CONFIG
+WORKDIR /home/${USER}
+
+ENTRYPOINT ["/bin/bash"]
\ No newline at end of file
diff --git a/setup/build_docker_image.sh b/setup/build_docker_image.sh
new file mode 100644
index 000000000..0852f27ab
--- /dev/null
+++ b/setup/build_docker_image.sh
@@ -0,0 +1,22 @@
+#!/bin/bash
+
+echo "Select CUDA version:"
+echo "1) CUDA 11.8"
+echo "2) CUDA 12+"
+read -p "Enter choice [1-2]: " choice
+
+case $choice in
+ 1)
+ DOCKERFILE=setup/Dockerfile.cuda11.8
+ ;;
+ 2)
+ DOCKERFILE=setup/Dockerfile.cuda12
+ ;;
+ *)
+ echo "Invalid choice"
+ exit 1
+ ;;
+esac
+
+export DOCKERFILE
+UID=$(id -u) GID=$(id -g) docker compose -f setup/docker-compose.yaml build
\ No newline at end of file
diff --git a/setup/docker-compose.yaml b/setup/docker-compose.yaml
new file mode 100644
index 000000000..d0b745c9e
--- /dev/null
+++ b/setup/docker-compose.yaml
@@ -0,0 +1,44 @@
+version: '3.9'
+
+services:
+ gem-stack-ubuntu-20.04-CUDA:
+ image: gem_stack
+ container_name: gem_stack-container
+ build:
+ context: ..
+ dockerfile: ${DOCKERFILE:-setup/Dockerfile.cuda11.8} # Default to cuda11.8 if not specified
+ args:
+ USER: ${USER}
+ USER_UID: ${UID:-1000} # Pass host UID
+ USER_GID: ${GID:-1000} # Pass host GID
+ 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"
+ - "~:/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}
+ - DBUS_SYSTEM_BUS_ADDRESS=unix:path=/var/run/dbus/system_bus_socket
+ - DBUS_SESSION_BUS_ADDRESS=unix:path=/run/user/${UID}/bus
+ - NVIDIA_DRIVER_CAPABILITIES=all
+ - NVIDIA_VISIBLE_DEVICES=all
+ # - LIBGL_ALWAYS_SOFTWARE=1 # Uncomment if you want to use software rendering (No GPU)
+ network_mode: host
+ ipc: host
+ user: "${USER}:${USER}"
+ # Un-Comment the following lines if you want to use Nvidia GPU
+ runtime: nvidia
+ deploy:
+ resources:
+ reservations:
+ devices:
+ - driver: nvidia
+ count: all # alternatively, use `count: all` for all GPUs
+ capabilities: [gpu]
diff --git a/setup/get_nvidia_container.sh b/setup/get_nvidia_container.sh
index 466b1989e..4f738e2c8 100755
--- a/setup/get_nvidia_container.sh
+++ b/setup/get_nvidia_container.sh
@@ -1,9 +1,14 @@
#!/bin/bash
-curl -s -L https://nvidia.github.io/nvidia-container-runtime/gpgkey | \
- sudo apt-key add -
-distribution=$(. /etc/os-release;echo $ID$VERSION_ID)
-curl -s -L https://nvidia.github.io/nvidia-container-runtime/$distribution/nvidia-container-runtime.list | \
- sudo tee /etc/apt/sources.list.d/nvidia-container-runtime.list
+curl -fsSL https://nvidia.github.io/libnvidia-container/gpgkey | sudo gpg --dearmor -o /usr/share/keyrings/nvidia-container-toolkit-keyring.gpg \
+ && curl -s -L https://nvidia.github.io/libnvidia-container/stable/deb/nvidia-container-toolkit.list | \
+ sed 's#deb https://#deb [signed-by=/usr/share/keyrings/nvidia-container-toolkit-keyring.gpg] https://#g' | \
+ sudo tee /etc/apt/sources.list.d/nvidia-container-toolkit.list
+
+sed -i -e '/experimental/ s/^#//g' /etc/apt/sources.list.d/nvidia-container-toolkit.list
+
sudo apt-get update
-sudo apt-get install nvidia-container-runtime
\ No newline at end of file
+sudo apt-get install -y nvidia-container-toolkit
+
+sudo nvidia-ctk runtime configure --runtime=docker
+sudo systemctl restart docker
\ No newline at end of file
diff --git a/setup/setup_this_machine.sh b/setup/setup_this_machine.sh
index e30b3aa23..00da094c9 100755
--- a/setup/setup_this_machine.sh
+++ b/setup/setup_this_machine.sh
@@ -1,30 +1,68 @@
#!/bin/bash
sudo apt update
-sudo apt-get install git python3 python3-pip wget zstd
+sudo apt-get install -y git python3 python3-pip wget zstd
+
+if [ ! -f /opt/ros/noetic/setup.bash ]; then
+ echo "ROS Noetic not found. Installing ROS Noetic..."
+ sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list'
+ wget https://raw.githubusercontent.com/ros/rosdistro/master/ros.asc
+ sudo apt-key add ros.asc
+ sudo apt update
+ sudo DEBIAN_FRONTEND=noninteractive apt install -y ros-noetic-desktop
+ sudo apt install -y python3-rosdep python3-rosinstall python3-rosinstall-generator python3-wstool build-essential python3-catkin-tools
+ sudo rosdep init
+ rosdep update
+fi
source /opt/ros/noetic/setup.bash
#install Zed SDK
-wget https://download.stereolabs.com/zedsdk/4.0/cu121/ubuntu20 -O ZED_SDK_Ubuntu20_cuda11.8_v4.0.8.zstd.run
-chmod +x ZED_SDK_Ubuntu20_cuda11.8_v4.0.8.zstd.run
-./ZED_SDK_Ubuntu20_cuda11.8_v4.0.8.zstd.run -- silent
+echo "Select CUDA version:"
+echo "1) CUDA 11.8"
+echo "2) CUDA 12+"
+read -p "Enter choice [1-2]: " choice
+
+case $choice in
+ 1)
+ wget https://download.stereolabs.com/zedsdk/4.0/cu118/ubuntu20 -O zed_sdk.run
+ ;;
+ 2)
+ wget https://stereolabs.sfo2.cdn.digitaloceanspaces.com/zedsdk/4.2/ZED_SDK_Ubuntu20_cuda12.1_v4.2.4.zstd.run -O zed_sdk.run
+ ;;
+ *)
+ echo "Invalid choice"
+ exit 1
+ ;;
+esac
+
+chmod +x zed_sdk.run
+./zed_sdk.run -- silent
#create ROS Catkin workspace
-mkdir catkin_ws
-mkdir catkin_ws/src
+mkdir -p ~/catkin_ws/src
+
+# Store current working directory
+CURRENT_DIR=$(pwd)
#install ROS dependencies and packages
-cd catkin_ws/src
+cd ~/catkin_ws/src
git clone https://github.com/krishauser/POLARIS_GEM_e2.git
git clone https://github.com/astuff/pacmod2.git
-git clone https://github.com/astuff/astuff_sensor_msgs.git
-git clone https://github.com/ros-perception/radar_msgs.git
-cd radar_msgs; git checkout noetic; cd ..
+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
catkin_make -DCMAKE_BUILD_TYPE=Release
source devel/setup.bash
-cd .. #back to GEMstack
+cd $CURRENT_DIR
+cd ..
#install GEMstack Python dependencies
-python3 -m pip install -r requirements.txt
\ No newline at end of file
+python3 -m pip install -r requirements.txt
+
+#install other dependencies
+sudo apt-get install -y ros-noetic-septentrio-gnss-driver
\ No newline at end of file
diff --git a/stop_docker_container.sh b/stop_docker_container.sh
new file mode 100644
index 000000000..1b1bad2c8
--- /dev/null
+++ b/stop_docker_container.sh
@@ -0,0 +1,3 @@
+#! /bin/bash
+
+docker compose -f setup/docker-compose.yaml down
\ No newline at end of file
diff --git a/testing/phone_accels.csv b/testing/phone_accels.csv
new file mode 100644
index 000000000..d204a9682
--- /dev/null
+++ b/testing/phone_accels.csv
@@ -0,0 +1,7507 @@
+Time (s),Linear Acceleration x (m/s^2),Linear Acceleration y (m/s^2),Linear Acceleration z (m/s^2),Absolute acceleration (m/s^2)
+0.002201583469,-0.0664243424,-0.03412830655,0.07313463449,0.1045256396
+0.01224258333,-0.0922835714,-0.03203695851,-0.07550275683,0.1234637216
+0.02228358341,-0.09904636966,0.03610824686,-0.07175761521,0.1275270331
+0.0323245835,-0.08599813434,-0.03348994592,-0.04047208786,0.1007732379
+0.04236558336,-0.08462590246,-0.0361651019,-0.005594615936,0.09219955364
+0.05240758345,-0.08420842954,-0.0004529033974,-0.02490446091,0.08781512911
+0.06244858354,-0.08082032438,0.001201036368,0.005032698512,0.08098577268
+0.0724895834,-0.08111612041,-0.03301944606,0.04709522903,0.09943877214
+0.08253058349,-0.08903633846,-0.01792649425,-0.01263057053,0.0916971105
+0.09257158334,-0.1110927028,-0.02580542548,0.009974765182,0.1144858269
+0.1026125834,-0.06326034092,-0.01276009549,-0.009633872509,0.06524953847
+0.1126535835,-0.08865454269,-0.03621001583,0.0304844588,0.1004992309
+0.1226945834,-0.07699550531,-0.001450109482,-0.01771530926,0.07902052162
+0.1327355835,-0.09176428383,-0.01173806615,0.006387498379,0.09273222805
+0.1427765836,-0.09357960675,-0.02660871414,-0.01845849037,0.09902465518
+0.1528175834,-0.08649733124,-0.0280952134,0.02749653161,0.09501151814
+0.1628585835,-0.07512889135,-0.0186474468,0.03168956995,0.08364392644
+0.1728995834,-0.07861014996,-0.01103915029,-0.01875377476,0.08156667569
+0.1829415835,-0.06834001359,-0.01997270909,0.01822284758,0.07349380069
+0.1929825835,-0.05667293629,-0.009626344219,0.02091899872,0.06117264681
+0.2030235834,-0.04544623656,0.005505144401,-0.04539076567,0.06446695774
+0.2130645835,-0.06330925654,-0.008154070135,0.001616755128,0.06385267982
+0.2231055833,-0.04946277578,-0.01391138485,-0.001374095678,0.05140020385
+0.2331465834,-0.05031392482,-0.002465789113,-0.04657775044,0.06860800232
+0.2431875835,-0.08595390564,0.004669166151,0.01599564314,0.08755418669
+0.2532285834,-0.03837317498,0.006278100628,-0.02995703995,0.04908502163
+0.2632695835,-0.06172574374,-0.005579586765,0.06524498641,0.08998948539
+0.2733105836,-0.03472834965,-0.01362246844,0.02423027694,0.04448298817
+0.2833515834,-0.05884786297,-0.008175640879,0.02887179673,0.06605673869
+0.2933925835,-0.08127026763,0.0001427999698,-0.02456707656,0.08490240305
+0.3034335834,-0.05281747415,0.03023359498,0.1071566588,0.1232327284
+0.3134755834,-0.05626373626,-0.01522236714,-0.009451439381,0.05904793126
+0.3235165835,-0.07640116781,0.01076920993,0.04982880235,0.09184782996
+0.3335575834,-0.04550724403,-0.006655711988,-0.05375403821,0.07074393533
+0.3435985835,-0.06970612873,-0.01538064396,-0.1776939601,0.1914958277
+0.3536395833,-0.1160912408,0.004206706211,-0.06707341075,0.1341406538
+0.3636805834,-0.03465949412,-0.03729231717,0.05282666981,0.07336657615
+0.3737215835,-0.06780748299,-0.008789269617,0.03756017447,0.07801200367
+0.3837625834,-0.08508853599,0.02079185832,-0.06003511727,0.106191222
+0.3938035835,-0.06890787416,-0.02655474616,-0.02740297616,0.07876784095
+0.4038445835,-0.08093153112,-0.03634346939,0.007625353932,0.08904440756
+0.4138855834,-0.0639604445,0.01420527139,0.01510920525,0.06723850295
+0.4239265835,-0.07924166752,-0.00305349824,0.01735629022,0.08117762335
+0.4339675833,-0.0794894981,-0.02074979492,0.02424489498,0.08565599354
+0.4440085834,-0.07789920162,-0.02664376088,0.004936219454,0.08247752342
+0.4540505835,-0.08828489816,-0.02177686748,-0.01482152224,0.09213106274
+0.4640915834,-0.06459623784,-0.02292090263,0.06885564208,0.09715524261
+0.4741325835,-0.08035221823,-0.01500802101,0.01437070191,0.08299540193
+0.4841735833,-0.1030981247,-0.002217172813,-0.05014396727,0.1146671558
+0.4942145834,-0.07317030251,-0.01156097774,-0.03577092648,0.08226243709
+0.5042555835,-0.0770083235,-0.02353193667,-0.01091792107,0.08126029124
+0.5142965834,-0.08303634603,0.001921194065,-0.01825032949,0.08503999221
+0.5243375835,-0.0888733656,0.001271614088,-0.06046079457,0.1074969757
+0.5343785835,-0.07665054699,-0.01372617429,-0.009263743758,0.07841894646
+0.5444195834,-0.07828065022,-0.03804272507,-0.01779541612,0.0888357246
+0.5544605835,-0.06252063617,-0.0004914584756,0.02097747087,0.06594790188
+0.5645015833,-0.0730601967,-0.006091008,0.04583281517,0.08646120324
+0.5745425834,-0.05276550702,-0.0573134942,0.01844387233,0.08005755289
+0.5845835835,-0.06722811072,-0.02855905292,0.03506282866,0.08102246804
+0.5946245834,-0.06812942703,-0.00162361647,-0.01417891324,0.06960816431
+0.6046665835,-0.06415196365,-0.03425900096,0.1241416508,0.1438759989
+0.6147075833,-0.06518322977,-0.03803251072,-0.01671192706,0.07729562614
+0.6247485834,-0.09506151047,-0.025347086,-0.06221495926,0.1164038947
+0.6347895835,-0.02106932698,-0.03186983778,0.02924894214,0.04811552468
+0.6448305834,-0.02791915282,-0.02916544572,0.04272502005,0.05878375334
+0.6548715835,-0.04577713415,0.01342007255,-0.04828513741,0.0678756131
+0.6649125835,-0.05773256597,0.0001746855676,-0.04918151557,0.0758412893
+0.6749535834,-0.06444909814,-0.02543758993,-0.04813310981,0.08436559424
+0.6849945835,-0.07333756942,0.02597598145,-0.03151766181,0.08394351498
+0.6950355833,-0.04585887183,0.0393336167,-0.03870155096,0.07174942212
+0.7050765834,-0.06558213321,0.01117218358,-0.004418740869,0.06667352663
+0.7151175835,-0.05126418415,0.03450494033,-0.04333839297,0.07547730646
+0.7251585834,-0.08005239311,0.06154615656,-0.0532196027,0.1141430731
+0.7351995835,-0.04805895067,0.06955979303,0.003665034771,0.08462659171
+0.7452405836,-0.04631950451,0.05439746034,0.003218307495,0.07151879259
+0.7552825834,-0.03796408916,0.05816643851,-0.01938293517,0.07211313896
+0.7653235835,-0.04243241259,0.0658148524,-0.01383919001,0.07952124002
+0.7753645834,-0.0604400735,0.05037794726,-0.01203941703,0.07959828903
+0.7854055834,-0.04503086041,0.04446166137,-0.0002110844851,0.06328240101
+0.7954465835,-0.06555487971,0.03401509898,-0.01053492844,0.07460197001
+0.8054875834,-0.06583746468,0.01231832922,0.02015944541,0.06994795371
+0.8155285835,-0.0264534797,0.002997182244,0.005645486712,0.02721472413
+0.8255695833,-0.03462193946,0.00716417307,0.03558849335,0.05016517643
+0.8356105834,-0.02468382902,0.002972879754,0.04936570287,0.05527297756
+0.8456515835,-0.03645440203,-0.009762419891,-0.02217907369,0.04377373161
+0.8556925834,-0.02628995866,-0.03986278058,0.008811753988,0.0485576998
+0.8657335835,-0.01911518751,-0.05288864116,-0.002261118293,0.05628242544
+0.8757745835,-0.02672740348,-0.02373698208,0.01555593252,0.03898442575
+0.8858155834,-0.00600100656,-0.03531026638,-0.02051554084,0.04127607549
+0.8958565835,-0.02213774119,-0.05799046473,0.02169726312,0.06575518847
+0.9058975833,-0.04292430961,-0.04932116353,-0.02874842048,0.07142510208
+0.9159395834,-0.04229161346,-0.05785792479,-0.08248608649,0.1092706479
+0.9259805835,-0.01589266819,-0.07473595846,-0.002103828192,0.07643602869
+0.9360215834,-0.01120330174,-0.04090983418,-0.0604859376,0.07387609322
+0.9460625835,0.01765277146,-0.05394737092,-0.02126983166,0.06061637492
+0.9561035833,0.03699446549,-0.1252302196,0.1993760204,0.238331693
+0.9661445834,0.01577084511,0.01215589539,-0.03757830083,0.04252780316
+0.9761855835,-0.09545790601,-0.01741456138,-0.211065774,0.2323020441
+0.9862265834,0.02379701653,-0.1256409774,0.1902514404,0.2292325539
+0.9962675835,0.03687681768,-0.05845389311,0.2791712183,0.2875992462
+1.006308584,-0.08748383875,0.02879274054,-0.1930920178,0.2139321651
+1.016349583,-0.04925350942,-0.05544175479,0.00749379158,0.07453759639
+1.026390583,0.008570775613,-0.07689528038,0.1426627064,0.1622929146
+1.036431583,-0.06732064747,0.02706539081,0.04207422495,0.08387398501
+1.046472583,-0.08660819993,0.01531570332,-0.0954850316,0.1298188828
+1.056513584,-0.06191156186,-0.07653500967,0.06124432147,0.1159375526
+1.066554583,-0.06151555005,-0.01728478974,-0.08590144515,0.107060661
+1.076595583,-0.117404626,0.0371334739,-0.103712064,0.1609935816
+1.086641792,-0.07325686871,-0.005413434478,0.03295958519,0.0805121627
+1.096682792,-0.06992883456,-0.05630980136,0.06125367701,0.1086869292
+1.106723792,-0.1238024666,-0.02478393517,-0.08603593111,0.152785718
+1.116764792,-0.0833914182,-0.01724486422,-0.05654316008,0.1022186036
+1.126805792,-0.05637433087,-0.01944655105,0.08177214146,0.1012072954
+1.136846792,-0.06983342445,-0.03198106279,0.09449977577,0.1217772687
+1.146887792,-0.09048466637,0.03364567372,-0.0667114681,0.1173453288
+1.156928792,-0.08143444648,-0.00117395645,-0.0346734041,0.08851662103
+1.166969792,-0.05325636707,0.003287734045,0.05379379928,0.07576821675
+1.177010792,-0.04667860578,0.05994264903,0.0009530961514,0.075979746
+1.187051792,-0.06917092578,0.09715482281,-0.05802309036,0.1326286379
+1.197092792,-0.04603226004,0.03220449951,-0.01715806961,0.05874094063
+1.207133792,-0.05637521708,0.03632795599,-0.009674218297,0.06776043084
+1.217174792,-0.04842833024,0.08306240268,-0.03332386672,0.1017602378
+1.227215792,-0.0336702503,0.07920749785,-0.01146638989,0.08682736647
+1.237256792,-0.01695518036,0.04733539428,-0.03092416942,0.05902899243
+1.247297792,-0.0249561174,0.04398899621,-0.06624953806,0.08334771069
+1.257338792,-0.00009637855925,0.0481829025,-0.002327776551,0.04823919492
+1.267379792,-0.00553707568,0.007351293107,0.0008250421286,0.009240206272
+1.277421792,0.01238058379,0.02614496598,0.02493077338,0.03818876225
+1.287462792,0.02977713757,0.02050612134,-0.1338866204,0.1386823927
+1.297503792,-0.005016572988,-0.054460391,0.01206339061,0.05600558531
+1.307544792,0.02685828061,-0.03264542526,-0.03628431201,0.05571034307
+1.317585792,0.04768632771,-0.06366199896,0.008920512199,0.08004006184
+1.327626792,0.02101758826,-0.00479639791,0.05353008986,0.05770801477
+1.337667792,-0.03227684054,-0.06424515822,-0.06322769701,0.0957443286
+1.347708792,0.09879834722,-0.1002139307,-0.001403331757,0.1407334881
+1.357749792,-0.03527316397,-0.1294271409,0.1180529451,0.1786954917
+1.367790792,0.02428763447,0.03170394131,0.004298872948,0.04016851244
+1.377831792,-0.03071247281,0.006469715713,-0.03685500026,0.04840872082
+1.387872792,-0.1261582002,-0.1886429627,-0.1380404824,0.2656261163
+1.397913792,-0.01147273961,-0.1639873557,0.09143115699,0.1881040485
+1.407954792,-0.1572511988,0.06009915342,-0.1307139212,0.2131337068
+1.417995792,-0.07949536359,0.07545714855,-0.04149827421,0.1171981265
+1.428036792,-0.1418608887,-0.0385124849,0.2857236081,0.3213186946
+1.438077792,-0.09855367779,-0.07594309785,0.08634349465,0.1514443151
+1.448118792,-0.1528510594,0.02572200215,-0.01514370382,0.1557382404
+1.458159792,-0.250980476,-0.06938848788,0.0388950938,0.2632846177
+1.468200792,-0.1109193146,-0.06583917316,0.2674756175,0.2969530216
+1.478241792,-0.0618487317,-0.07022890636,-0.05016969502,0.1061808043
+1.488283792,-0.1985284665,0.003765725652,0.02632825792,0.2003020466
+1.498324792,0.002832181128,-0.04558661085,0.04339744985,0.06300396013
+1.508365792,-0.01639344567,-0.09991114545,-0.09401913464,0.138168664
+1.518406792,-0.09982549287,0.04786962879,-0.01917126596,0.1123573221
+1.528447792,-0.0006007009093,0.02699708803,-0.1719999415,0.1741068163
+1.538488792,0.03477643386,-0.03609964963,-0.03697662234,0.06228848734
+1.548529792,0.03590646311,0.0259447628,-0.007637048364,0.04495252292
+1.558570792,0.01279191714,0.05957821218,-0.1857637024,0.1955028124
+1.568611792,-0.03917865635,-0.04930764184,-0.1011889905,0.1191865028
+1.578652792,0.0754789477,0.01509646928,-0.1348543346,0.1552760976
+1.588693792,0.01175639352,0.09143207062,0.1185546362,0.1501773555
+1.598734792,0.2758363685,0.1440609218,0.2889518559,0.4246556563
+1.608775792,-0.1722000259,-0.1983202691,-0.6065153074,0.6609422034
+1.618816792,0.2075612087,0.1678912858,0.7266352433,0.7741239668
+1.628857792,0.004503790447,-0.1098630243,-0.3045797092,0.3238193439
+1.638898792,-0.02198230575,0.1349939825,-0.2852821434,0.316373985
+1.648939792,-0.02011472334,-0.1644662792,0.9954908037,1.009185661
+1.658980792,0.1017289077,-0.08874867372,-0.9542334348,0.9637357241
+1.669021792,-0.2874145133,-0.03643261202,0.7107746708,0.7675513471
+1.679062792,0.1413958066,-0.04586700311,-0.3695370126,0.3983141471
+1.689103792,-0.1254369644,-0.1228232133,0.254819904,0.3094400705
+1.699144792,-0.1202641246,-0.05038323716,-0.3653474826,0.3879184363
+1.709186792,-0.134170457,-0.04363720397,0.2245792741,0.2652202244
+1.719227792,-0.0306198858,-0.05337192267,-0.1006913924,0.1180037967
+1.729268792,-0.1436335909,-0.03147092063,0.0177135551,0.1481040084
+1.739309792,-0.04051468117,0.04011462199,0.01457886279,0.05884866632
+1.749350792,-0.1620958545,-0.1393616973,-0.2508227473,0.3295584915
+1.759391792,-0.02211850019,0.01322893255,0.3347624516,0.3357530815
+1.769432792,-0.05244273615,0.1045631811,-0.02433552682,0.1194818701
+1.779473792,-0.1634307921,0.05789928471,-0.2900265741,0.3379014127
+1.789514792,0.01614005109,-0.1590099134,0.4650144428,0.4917144352
+1.799555792,-0.05199210769,-0.1440524799,-0.5630751729,0.5835305875
+1.809596792,-0.1344733519,0.3812195302,0.1766864848,0.4411683652
+1.819637792,0.107150775,-0.002127600778,0.2639772284,0.2849031281
+1.829678792,-0.07697274685,-0.09590646054,-0.2437739289,0.2730358609
+1.839719792,-0.01189161038,0.01524540883,0.4392767537,0.4397020573
+1.849760792,-0.1697883235,0.01088392499,-0.83115013,0.8483849794
+1.859801792,0.09956439642,0.04893959616,0.7587066364,0.7667750082
+1.869842792,-0.03581276148,-0.0275590694,-0.1136763042,0.1223288941
+1.879883792,-0.09358512506,0.09108206908,-0.2608179778,0.2916849953
+1.889924792,0.02545353273,0.003059656089,-0.05125201464,0.05730630705
+1.899965792,-0.08235460636,-0.006300986996,0.3172857088,0.3278600382
+1.910006792,0.2052942067,-0.1648936741,0.1896082467,0.3244794635
+1.920047792,-0.1057489051,0.1905282695,-0.6847305876,0.7185679022
+1.930088792,0.02243719172,0.1059959499,0.4695401877,0.4818781556
+1.940129792,0.05509938204,-0.2290636134,-0.1154369009,0.2623580739
+1.950170792,0.1039127971,0.06591638382,-0.02171889782,0.1249581913
+1.960212792,-0.1330834231,-0.02166750628,-0.2776819324,0.3086874373
+1.970253792,0.03473927664,-0.06585355366,-0.1399782497,0.1585478422
+1.980294792,0.1258480876,-0.1030406392,0.4656611449,0.4932498518
+1.990335792,-0.1098262325,0.01687891074,-0.1188727248,0.1627188485
+2.000376792,0.09426769612,-0.01791639866,-0.08727846444,0.1297109333
+2.010417792,-0.05722455257,-0.1100973788,0.1552184325,0.1987180013
+2.020458792,-0.05291192953,-0.05470791095,-0.2450579774,0.2566048326
+2.030499792,-0.0618664378,0.05638409754,0.3483180517,0.3582346825
+2.040540792,0.009356842395,-0.07291592122,-0.155230127,0.1717576036
+2.050581792,-0.1142639585,-0.008184210705,0.07589042723,0.1374139384
+2.060622792,-0.1366060873,0.007366806502,-0.08427474976,0.1606789544
+2.070663792,-0.118994895,-0.0853305285,-0.2211007655,0.2651916903
+2.080704792,-0.03880750434,-0.01865824588,0.2314035594,0.2353757843
+2.090741417,-0.09754894341,0.03612166805,-0.11887214,0.1579593522
+2.100782417,-0.04916830452,0.04363311091,-0.0622892189,0.09056112482
+2.110823417,-0.03814985703,-0.00584812928,0.107758922,0.1144622098
+2.120864417,-0.05918229173,-0.04345649759,-0.05375403821,0.09099729371
+2.130905417,-0.03936773155,0.0004043806437,-0.02696092665,0.04771659436
+2.140946417,-0.007254165374,0.02411837585,0.09010442376,0.09355814315
+2.150987417,-0.03219957506,-0.05143006235,-0.1483508778,0.1602805256
+2.161028417,0.002040824443,-0.06623991757,0.05881597281,0.08860705559
+2.171069417,0.01543376226,-0.04846572502,0.1049189293,0.1165980671
+2.181110417,-0.01893689311,0.03812942832,-0.07710606337,0.08807839822
+2.191151417,-0.01510703081,0.023940118,0.1969798315,0.1990035317
+2.201192417,0.02068269812,-0.07643519587,-0.1425176954,0.1630380529
+2.211233417,-0.0196500981,-0.01711470885,0.09069557726,0.0943648629
+2.221274417,0.02120807958,0.05322739595,0.1118051952,0.1256317635
+2.231315417,-0.03579228709,-0.07646791287,-0.1687138063,0.1886604832
+2.241356417,-0.01829992119,-0.02136250089,0.113748225,0.1171746655
+2.251397417,-0.05701687591,-0.05244081753,-0.02651361465,0.08187756252
+2.261438417,-0.01568574985,0.04514738445,-0.1795019192,0.1857559368
+2.271480417,-0.01509450498,0.007712724125,0.2556484544,0.2562098016
+2.281521417,-0.01279592796,0.02099901421,-0.1604867738,0.1623597824
+2.291562417,-0.05125208773,-0.01226718435,-0.06648167253,0.08483556501
+2.301603417,-0.01158966565,0.004587158952,0.008819355369,0.01526903422
+2.311644417,-0.03013899799,-0.06741441306,-0.0555485487,0.09240510565
+2.321685417,-0.01649763574,0.02322783577,-0.05001065075,0.05755666363
+2.331726417,-0.01523779831,0.0502645935,-0.04536913097,0.06940517201
+2.341767417,-0.01515529775,-0.02862157244,-0.08459166884,0.09057940106
+2.351808417,-0.009632182298,0.01181492049,0.2249710375,0.2254868932
+2.361849417,-0.06125781574,-0.06212641049,-0.2124310988,0.2296501309
+2.371890417,-0.05973062351,0.006120929299,0.05565847635,0.08187233446
+2.381931417,0.01348667599,-0.01041735373,0.1634255844,0.1643116957
+2.391972417,-0.01726000302,0.0506880781,0.03439624608,0.0636418943
+2.402013417,-0.07064750304,-0.05917586893,0.1072999156,0.1414430098
+2.412054417,-0.008597974302,-0.06613329724,-0.1209788918,0.13814279
+2.422095417,-0.0993501782,-0.0907099669,0.1614854783,0.2101816255
+2.432136417,-0.01395647236,-0.02281926158,-0.1221781558,0.1250719935
+2.442177417,-0.02586812773,-0.02208038365,0.2285536265,0.2310702568
+2.452218417,-0.01440210328,-0.1018493147,-0.08594003677,0.1340387758
+2.462259417,-0.06938240312,-0.04998820293,-0.041481902,0.09504465523
+2.472300417,-0.05028174229,-0.02504526917,-0.1157310158,0.128643644
+2.482341417,-0.04239520054,-0.0001596472599,0.07841759384,0.0891442513
+2.492382417,0.01494768505,0.03102454967,-0.01409062028,0.03720889074
+2.502423417,-0.09960196478,-0.05098004602,-0.04253030777,0.1197010591
+2.512464417,-0.04412052202,-0.006738550588,0.06120865345,0.07575307112
+2.522505417,0.2263143622,0.1173651116,-1.019012983,1.050419068
+2.532546417,-0.09735845209,0.1761699929,1.671204985,1.683282696
+2.542587417,0.1074912017,-0.1517757016,-1.082791488,1.098648091
+2.552628417,-0.03711059667,0.295540462,-0.07241191864,0.3065368607
+2.562669417,0.02702861731,-0.383828302,0.5440033096,0.6663289821
+2.572710417,-0.03779437372,0.188852421,-0.7074014121,0.7331510141
+2.582751417,0.06709296238,0.1157357027,0.4202206779,0.4410007217
+2.592792417,-0.1153184673,-0.03943578766,0.3605124199,0.380555824
+2.602833417,-0.02474675054,-0.1796909304,-0.3033541328,0.3534472549
+2.612874417,-0.08366327718,0.1757742826,0.07894910574,0.210069283
+2.622915417,-0.05139469584,0.009426241536,0.07806032896,0.09393446517
+2.632956417,0.001191224009,-0.01927093358,0.0812037921,0.08346762095
+2.642997417,-0.01091791193,0.0268332929,-0.1219220477,0.125316448
+2.653038417,-0.1873033108,0.0253114728,-0.1422767901,0.2365711012
+2.663079417,0.04351752791,-0.03392008172,0.08540910959,0.101681184
+2.673120417,-0.04143273971,-0.05881029918,0.03122296214,0.07842318901
+2.683162417,-0.09560450667,-0.04506704005,-0.1183154851,0.1586499726
+2.693203417,-0.01799157193,0.02965713261,-0.1726536602,0.1761037437
+2.703244417,0.03022482416,-0.08894362355,0.1665415657,0.1912082667
+2.713285417,0.00290915424,-0.00003056997433,0.1294234407,0.1294561359
+2.723326417,0.02696619828,-0.0561457961,-0.1286375749,0.1429235878
+2.733367417,-0.03420780128,-0.05195650362,0.02539621174,0.06719091835
+2.743408417,0.1129252659,-0.04725833894,0.04350913167,0.129917323
+2.753449417,-0.08168716497,-0.0332051317,-0.04016510904,0.09689483823
+2.763490417,0.06802904679,-0.0323762432,0.1791411459,0.1943391945
+2.773531417,0.002830600552,-0.04235067034,-0.2287617874,0.2326661706
+2.783572417,-0.09444702292,-0.05592291668,-0.01305741727,0.1105355549
+2.793613417,0.03301642195,-0.004701654743,0.02600841522,0.04229216639
+2.803654417,-0.04563977483,-0.02628465048,0.05909254611,0.0791568121
+2.813695417,-0.06904997064,0.007517125625,-0.1055638772,0.1263650972
+2.823736417,-0.07508159285,0.005278162798,0.04247592866,0.08642516476
+2.833777417,-0.05566922061,-0.03094776842,-0.0407498306,0.07561332679
+2.843818417,-0.08628481236,0.02602198259,0.06403051972,0.1105536968
+2.853859417,-0.02597565254,0.04177613572,0.01658387303,0.05191343647
+2.863900417,-0.1091490335,-0.01673729849,-0.00002806663513,0.1104248589
+2.873941417,-0.0315396985,0.03165744681,-0.0645450747,0.07850486092
+2.883982417,-0.09486267773,0.02641666965,0.1043049717,0.1434443975
+2.894023417,-0.02196459051,-0.002132004462,-0.09657612205,0.09906531193
+2.904064417,-0.07255227922,0.009128179718,0.08904081523,0.1152190247
+2.914105417,-0.06686324903,0.005203236211,-0.1287574428,0.1451766056
+2.924146417,-0.05135169139,-0.01613001946,-0.06978125632,0.08812830119
+2.934187417,-0.008991537597,-0.03118482733,0.05520765603,0.06404081892
+2.944228417,-0.05466469637,-0.01492453373,-0.04433300436,0.07194710565
+2.954269417,-0.02987153356,-0.01644856481,-0.05226709127,0.0624076328
+2.964310417,-0.0161775555,-0.02375520894,0.05880603254,0.06545359208
+2.974351417,-0.03958434348,-0.03487339715,-0.04238354266,0.06767155064
+2.984392417,0.01927754824,-0.03954952514,0.03291339219,0.05494615719
+2.994433417,-0.01770088308,-0.03839625321,0.03126915514,0.05258662935
+3.004474417,-0.01314399261,-0.02923717462,-0.02112306654,0.03838959314
+3.014515417,-0.03089440344,-0.01953219448,0.06958771348,0.0786029303
+3.024556417,-0.001507668011,-0.04729468304,0.005525618792,0.04764024107
+3.034597417,-0.03853534386,-0.07163930959,-0.002855195403,0.08139604134
+3.044638417,-0.01891360475,-0.05361391517,-0.003452780843,0.05695698412
+3.054679417,-0.04888985828,-0.0668577764,0.008075004816,0.08321890537
+3.064720417,-0.02307358805,-0.05695820276,-0.001206865311,0.06146611954
+3.074761417,-0.01930578846,-0.04534592483,0.03517217159,0.06054789857
+3.084802917,-0.04549343912,-0.0474586883,-0.049100824,0.08205407373
+3.094843917,-0.04398902362,-0.05982586004,-0.003890152574,0.07435926987
+3.104884917,-0.0372898321,-0.04649128474,0.02155985355,0.06337821724
+3.114925917,-0.04026014457,-0.04223724349,0.02440510869,0.06324929493
+3.124966917,-0.03177338613,-0.01555124561,-0.01226804316,0.03744187748
+3.135007917,-0.01611352849,-0.003119544368,0.0112360096,0.01989033105
+3.145048917,-0.03530697732,0.007021564962,0.02740297616,0.04524166359
+3.155089917,-0.003313818108,0.01253125923,0.01602955699,0.0206145712
+3.165130917,-0.03230599439,0.04726399429,-0.01809537828,0.06004169505
+3.175171917,0.01519246412,0.05997946822,-0.02737198591,0.06765776516
+3.185212917,0.0367959982,0.04720566832,-0.03081190288,0.06731785769
+3.195253917,0.05550057412,0.05410183791,-0.004463764429,0.07763535139
+3.205294917,0.08261317207,0.08817561004,-0.02391920507,0.123174684
+3.215335917,0.06327547059,0.06568992298,-0.03558966279,0.09790595108
+3.225376917,0.07485461125,0.06050961882,-0.0342395407,0.1021615042
+3.235417917,0.06804180102,0.05945941321,-0.03513533413,0.09695153537
+3.245458917,0.03690620908,0.04043903282,-0.04725310385,0.07232039455
+3.255499917,0.02717246795,0.02834534632,0.003793673515,0.03944862014
+3.265540917,0.01537729095,0.0009780747257,-0.01791119099,0.02362685907
+3.275581917,-0.02917782538,0.009445181033,-0.02030679524,0.03678209988
+3.285622917,-0.04006532265,-0.00236203758,-0.02449807942,0.04702090169
+3.295663917,-0.0586754569,-0.04282037535,0.009632703066,0.07327470748
+3.305704917,-0.04454908638,-0.05254053997,0.0139719218,0.07028758096
+3.315745917,-0.06726351835,-0.04631352939,0.02190308511,0.08455216758
+3.325786917,-0.0418629486,-0.04468738217,0.05393764079,0.08160108874
+3.335827917,-0.05456016826,-0.04838744542,0.02160663128,0.0760592095
+3.345868917,-0.03970383681,-0.04536797066,0.03074115157,0.06767322823
+3.355909917,-0.04070914677,-0.02036450909,-0.01999981642,0.0497186134
+3.365950917,-0.00933318858,-0.006586367665,0.03030202568,0.03238365959
+3.375991917,-0.02468378333,0.01575930599,-0.01340298772,0.03220690865
+3.386032917,-0.003656793851,-0.004310731832,-0.005019249916,0.007559591253
+3.396073917,0.003190505812,-0.01860724719,-0.03180943787,0.03698985419
+3.406114917,0.0001297168247,-0.02069924391,0.007710138559,0.02208895112
+3.416155917,-0.01186167081,-0.01746789895,-0.01129623592,0.02394643343
+3.426196917,0.04970769189,0.02811612633,0.02882268012,0.06396966533
+3.436237917,0.162590602,-0.004162550597,-0.1508113861,0.2218042039
+3.446278917,-0.2638300247,-0.06144497233,0.3238638264,0.4222197824
+3.456319917,0.2257968471,0.03167214707,-0.2292359966,0.3233210219
+3.466360917,-0.1723757164,0.009250267753,-0.0005209869146,0.1726245246
+3.476401917,0.08094519898,-0.001536511229,-0.03404892147,0.08782832777
+3.486442917,-0.04683670901,-0.0185772528,0.2338927191,0.2392584287
+3.496483917,-0.0314901799,-0.04965300215,-0.2045490521,0.2128317805
+3.506524917,-0.04286295952,0.007649263563,0.08554944277,0.09599193555
+3.516565917,-0.01282403114,0.02584372474,-0.01055247009,0.030719839
+3.526606917,-0.01623611902,-0.04424081021,0.008163297772,0.04782781909
+3.536647917,-0.06771951894,0.07081732811,-0.1187774152,0.1539776008
+3.546688917,0.02076244866,0.01901769432,-0.0578505975,0.06433850793
+3.556729917,-0.04707424301,-0.02764416466,-0.001274108291,0.05460592959
+3.566770917,0.04861907738,0.04317459784,0.02671768248,0.07029719156
+3.576811917,-0.06497849043,0.01050699885,-0.05531232119,0.08597705576
+3.586852917,0.04999127272,-0.03244931513,-0.03031781316,0.06686744495
+3.596893917,0.03488933081,-0.01529484521,0.1298479486,0.1353206837
+3.606934917,-0.1476178653,-0.01674122709,-0.103523199,0.1810755521
+3.616975917,0.3848607375,0.06438659688,0.06997538388,0.3964340746
+3.627016917,0.1489346217,-0.002490292601,0.1732535845,0.2284831015
+3.637057917,-0.4311065854,0.02090136571,-0.0590598017,0.4356349564
+3.647098917,0.2468337586,-0.05207155673,0.1132360089,0.2765153614
+3.657139917,-0.03056808312,-0.005406591408,-0.1243246686,0.1281415708
+3.667180917,-0.2534421172,-0.01392922799,0.03015233696,0.2556092596
+3.677221917,0.05796006834,-0.03634158731,0.2052898943,0.2163885884
+3.687262917,-0.1444392367,-0.03260049306,-0.1440806562,0.2066028091
+3.697303917,-0.1054018637,0.02294813787,-0.0789724946,0.1336892845
+3.707344917,-0.09220200274,-0.06963833758,0.10948502,0.1591781297
+3.717385917,0.01621850428,-0.01062202455,0.04572815001,0.04966820905
+3.727426917,0.01736771056,0.05611362727,-0.009805195928,0.05955265236
+3.737467917,-0.06148737377,-0.01642652811,-0.04467448175,0.07775819751
+3.747508917,0.002139304345,-0.032937448,0.03331801951,0.04689928067
+3.757549917,0.2002094679,0.07028043495,0.005926153064,0.2122693804
+3.767590917,-0.2093130711,-0.01248563267,0.05338683307,0.2163746905
+3.777631917,0.103785611,-0.03396517837,-0.2217404509,0.2471718308
+3.787672917,0.004146205802,-0.0374133454,0.1906525594,0.1943330848
+3.797713917,-0.0213432873,-0.04672381206,-0.1931534135,0.1998671851
+3.807754917,0.0229347715,0.04816928032,0.1146101046,0.1264189835
+3.817795917,0.04598309775,-0.05351612963,-0.06576421916,0.09645389537
+3.827836917,-0.03519263685,-0.05808119707,-0.06022515178,0.09076902582
+3.837877917,-0.01945533101,-0.0430500887,-0.01232710004,0.04882394327
+3.847918917,-0.0332241717,-0.03736362579,-0.01771238565,0.05304351726
+3.857959917,-0.0448558368,-0.07305002346,-0.03402904093,0.09222975468
+3.868000917,-0.01561293374,-0.08289558345,0.02314854205,0.08747168944
+3.878041917,-0.06116024947,-0.03467309346,0.02584586263,0.07490532785
+3.888082917,-0.04482777016,-0.001121724369,0.01552201867,0.04745229506
+3.898123917,-0.04728959413,-0.07066140845,0.0864803195,0.1212773104
+3.908164917,-0.1069528833,-0.07207419625,0.1164157248,0.1737418487
+3.918205917,-0.02951766738,-0.04055518228,-0.09554584265,0.1079121103
+3.928246917,-0.112165804,0.0517889809,0.1641687655,0.2054620396
+3.938287917,0.05134230844,0.008336548945,-0.03131651759,0.06071453663
+3.948328917,-0.0894595581,-0.04573015999,0.07496598244,0.1253561271
+3.958369917,-0.07743472257,-0.04625477401,-0.1118408632,0.1436802668
+3.968410917,-0.04756012836,0.04419784231,-0.1862379116,0.1972307653
+3.978451917,-0.02520932925,-0.02387113913,0.05461299419,0.06471414605
+3.988492917,-0.06032808105,0.01638119392,0.05507024646,0.08330998093
+3.998533917,0.01580988441,-0.0303935346,-0.2501444703,0.2524796535
+4.008574917,0.007431071056,-0.06232958296,-0.02725387216,0.06843223858
+4.018615917,-0.1355393268,0.09157350015,0.3038692725,0.3450987537
+4.028656917,0.08568620366,-0.1122266241,-0.5960663331,0.6125618451
+4.038697917,-0.2842982031,-0.09554315658,0.3004147375,0.4245032127
+4.048738917,0.003782792212,0.01276914041,-0.05734598279,0.05887208342
+4.058779917,0.04351965666,0.0465694273,0.1248351306,0.1401659085
+4.068820917,-0.08679253341,-0.02909571768,0.140414452,0.1676177883
+4.078861917,-0.1034637127,-0.1163987952,0.05271147966,0.1644138664
+4.088902459,-0.005983739002,-0.06271381812,-0.2839495629,0.2908542288
+4.098943458,-0.1349961296,0.04729646461,0.1814379323,0.2310424935
+4.108984458,-0.04648610448,-0.006881259196,-0.1318710852,0.1399939025
+4.119025458,0.1146249876,-0.042767924,0.2889156032,0.3137518268
+4.129066458,-0.08122125152,0.03565675045,-0.2505619615,0.2657999099
+4.139107459,0.05505390166,0.03124502624,-0.3248081517,0.3309192034
+4.149148458,0.02672689185,-0.05779761625,0.4690016592,0.4733048146
+4.159189458,-0.05096815059,-0.06362331597,-0.1794457859,0.1970950755
+4.169230458,0.02019568901,-0.001062722309,-0.3105888927,0.3112466152
+4.179271458,-0.06810822174,0.01045155994,0.2800857228,0.2884371285
+4.189312459,0.06831845655,-0.06087583724,0.2113902944,0.2303456873
+4.199353458,-0.0005035000853,-0.03596027576,-0.231547401,0.2343236946
+4.209394458,-0.1360466275,0.03167761057,0.09823205352,0.1707679484
+4.219435459,0.05016245909,-0.05147091977,-0.1158304185,0.1363165937
+4.229476458,-0.01709327515,-0.08490289603,0.1673788869,0.1884578828
+4.239517458,-0.0518398334,0.04555054997,0.06724765778,0.0963559464
+4.249558458,0.03551666396,0.02639001,-0.2009916061,0.2058044989
+4.259599458,-0.07143066449,-0.121836989,-0.01253292203,0.1417873967
+4.269640459,0.04675961712,-0.0005127459951,0.1702370059,0.1765428075
+4.279681458,-0.04406759558,0.04298823612,-0.1803293002,0.1905481512
+4.289722458,-0.02756435017,0.01153192439,-0.01131904006,0.03195151559
+4.299763459,0.05696302671,-0.01796837493,-0.02224514723,0.0637377085
+4.309804458,-0.08017313811,-0.07954887475,0.05439957082,0.1253597577
+4.319845458,0.01882064315,-0.05666845495,-0.07987062693,0.09972385593
+4.329886458,0.01392412995,0.04924112063,0.1231125408,0.1333239178
+4.339927458,-0.05669298585,-0.04278242326,-0.185993498,0.1990929724
+4.349968459,0.02956654645,-0.03473413291,0.1897316229,0.1951377191
+4.360009458,0.06831414423,-0.0467537425,0.04678649604,0.0950879117
+4.370050458,-0.04605183908,0.02996005492,-0.01188154221,0.05620985517
+4.380091458,-0.0771173558,-0.04868338762,-0.1706983513,0.1935331649
+4.390132458,0.005139848739,-0.09636417875,0.2512776607,0.2691708301
+4.400173459,0.03984578711,0.03097008834,-0.09450094521,0.1071319829
+4.410214458,-0.1147700076,-0.02457787564,0.001159502864,0.1173778986
+4.420255458,0.06094646978,-0.08144554705,-0.01710310578,0.1031521475
+4.430296459,0.04490629644,0.05316048187,0.1676174533,0.1814889059
+4.440337458,-0.1135917845,0.1735204003,-0.4194541079,0.4679253909
+4.450378458,-0.03197159761,-0.1922159952,0.2248143321,0.2975074046
+4.460419458,0.169339166,-0.04973596866,0.3044504857,0.3519083943
+4.470460458,-0.2228191342,0.2481699022,-0.6304976624,0.7132769233
+4.480501459,-0.08005049276,-0.1323447827,0.1272313195,0.2002773866
+4.490542458,0.325396272,0.07746688225,0.4075982934,0.5272762279
+4.500583458,-0.3149724406,-0.08988113321,-0.29892896,0.4434464788
+4.510624459,0.1846024088,0.08920835624,0.08113654912,0.2204978906
+4.520665458,-0.03801048316,0.1249351454,-0.1387561816,0.1905436047
+4.530705458,-0.08651718437,-0.2244089374,0.1622707593,0.2901316834
+4.540746458,0.2244260405,0.0774215572,0.1448975122,0.2781302468
+4.550787458,-0.05077888353,0.2131949279,-0.2147810948,0.3068574441
+4.560828459,-0.097619311,-0.105226566,-0.1159842002,0.1845385997
+4.570869458,0.2532245643,-0.0820243209,0.4194476759,0.4967766319
+4.580910458,-0.09023950358,0.07786272048,-0.264026345,0.2896820362
+4.590951459,-0.006415528469,0.1330717835,-0.06329201639,0.1474962301
+4.600992458,0.1736665258,-0.01586521368,0.1675355923,0.2418262639
+4.611033458,-0.0679393103,-0.127511054,0.02623119414,0.1468430942
+4.621074458,0.1044894696,0.01920373628,-0.1361857456,0.1727234496
+4.631115458,0.02674757637,0.04705555933,0.03116916776,0.062459391
+4.641156459,0.1044288504,0.05076776468,0.1512277079,0.1906635003
+4.651197458,0.0009007635713,0.08580382406,-0.1806374484,0.1999824877
+4.661238458,0.03518350971,-0.16129559,0.0512373966,0.1728566386
+4.671279458,0.123315759,0.007661634078,0.02698373079,0.1264658008
+4.681320458,0.04402355874,0.2529548797,0.02968865275,0.258467911
+4.691361459,0.01185949638,-0.0695258609,-0.1054808468,0.1268885417
+4.701402458,0.1981115235,0.01167297933,0.3070647758,0.3656134718
+4.711443458,0.01742391692,0.1360314339,-0.5506556869,0.5674767214
+4.721484459,-0.01736334343,-0.02455948432,0.2807183915,0.2823251128
+4.731525458,0.3064771124,-0.07011689563,0.416788947,0.522070518
+4.741566458,-0.07094270521,0.3604092531,-0.3918248445,0.5370795154
+4.751607458,0.06723834791,0.1155881153,-0.4163802266,0.4373260808
+4.761648458,0.1567649115,-0.3364728353,0.6449168962,0.7441149168
+4.771689459,0.2508027937,0.254343429,0.05080879569,0.3607965561
+4.781730458,0.02210612054,0.4286821105,-0.6470429438,0.7764802661
+4.791771458,0.1630958746,-0.3289180134,0.6289113128,0.7282285103
+4.801812459,0.2622553878,0.1267341144,-0.08540794015,0.3035357317
+4.811853458,-0.1660187698,0.4648640232,-0.6057347041,0.7813931941
+4.821894458,0.3233267596,-0.2250753555,0.648670224,0.7589283027
+4.831935458,0.3714431683,-0.02926299373,0.1284949028,0.3941285199
+4.841976458,-0.1434392897,0.4179673802,-0.6998889095,0.827717371
+4.852017459,0.3697429807,-0.09919663397,0.5335531658,0.6566801541
+4.862058458,0.3276568786,0.02718942488,0.05993396044,0.334201099
+4.872099458,-0.1730598955,0.1100905632,-0.6678654635,0.6986515132
+4.882140458,0.5599882816,0.09838260105,0.9366584587,1.095716697
+4.892181458,0.2038580026,0.0859604198,-0.632073487,0.6696746763
+4.902222459,0.05374617188,0.05589400951,0.2410614055,0.2532259713
+4.912263458,0.5901460272,0.1879685047,0.09106629074,0.6260172214
+4.922304458,-0.1220350909,0.09984614085,-0.3981047541,0.4281929594
+4.932345459,0.4779006463,0.1626246986,0.3224868071,0.5990271789
+4.942386458,0.1223428645,0.0003174033109,0.04452303886,0.1301928502
+4.952426458,0.2506570884,0.1479893828,-0.2006659162,0.3535486435
+4.962467458,0.2472549956,0.1604426639,0.01487414718,0.2951239088
+4.972508458,0.1547350505,0.1424963257,0.03837761521,0.2138246479
+4.982549459,0.3191834957,0.1252579208,-0.06745523393,0.3494536582
+4.992590458,0.1493900833,0.07905285727,0.208566674,0.2684526192
+5.002631458,0.3347533885,0.1945951725,-0.05622565627,0.3912651743
+5.012672459,0.1326269657,0.1116692109,-0.2015792513,0.2658836573
+5.022713458,0.3091267599,0.05591316828,0.3179891288,0.4469929777
+5.032754458,0.227874509,0.2306121023,-0.1189504927,0.3453374484
+5.042795458,0.2452768826,0.2208713719,-0.03317827106,0.3317313819
+5.052836458,0.3746997385,0.1023364335,0.179684937,0.4279711629
+5.062877459,0.2162650085,0.1150671558,-0.1544249654,0.2895825861
+5.072918458,0.3116814084,0.2642310707,0.09226029217,0.4188977447
+5.082959458,0.2951926623,0.2293437133,-0.004885933399,0.3738463842
+5.093000208,0.3227683871,0.09814707703,0.0424145329,0.3400165776
+5.103041208,0.3189948499,0.2221484769,0.05498546183,0.3925952892
+5.113082208,0.3669682577,0.2852610751,-0.1113216305,0.4779456962
+5.123123209,0.3798092549,0.1507874217,0.09853903234,0.4203592006
+5.133164208,0.3828983389,0.2126910624,0.2054179484,0.4837821405
+5.143205208,0.3944625235,0.3234816012,-0.1614708602,0.5350830472
+5.153246208,0.3842512384,0.1809647098,0.1109643656,0.4389878482
+5.163287208,0.4772561004,0.1863509456,0.1206953019,0.5263719371
+5.173328209,0.4449788122,0.3262584805,0.05094269693,0.5541172238
+5.183369208,0.5490770117,0.2851929368,0.04330857217,0.6202388317
+5.193410208,0.5600305277,0.2251458693,0.2236869889,0.6437085703
+5.203451209,0.5672037091,0.3471559541,0.02101196945,0.6653411208
+5.213492208,0.6095415339,0.3742823204,0.04601700246,0.7167605607
+5.223533208,0.6255999615,0.2776534821,0.1340392327,0.6974476926
+5.233574208,0.6073903432,0.3324533862,0.1091961676,0.7009793764
+5.243615208,0.6317276242,0.4927741722,-0.1174249542,0.8097498354
+5.253656209,0.6225198676,0.3241870678,-0.05694720268,0.7041812439
+5.263697208,0.688053341,0.2908342939,0.2901856184,0.8013798598
+5.273738208,0.6270052667,0.4675241774,-0.265158366,0.8258470924
+5.283779209,0.6767606865,0.3959920089,-0.08537870407,0.7887358373
+5.293820208,0.7088515947,0.3249912427,0.1436538094,0.7929226369
+5.303860208,0.6782843978,0.4472131795,-0.03925762117,0.8133944388
+5.313901208,0.7272728822,0.472268462,-0.1497243887,0.8799890556
+5.323942208,0.6751064361,0.3535161533,0.06808264017,0.7650997429
+5.333983209,0.7687360731,0.4287490246,0.07946775377,0.8837963567
+5.344024208,0.6462328852,0.5577197812,-0.04790857673,0.8549640507
+5.354065208,0.7610385791,0.5068828458,-0.1493881738,0.9265132296
+5.364106209,0.7285149039,0.3938080373,0.2722989857,0.8717599859
+5.374147208,0.7587870356,0.4390826626,-0.06164719462,0.8788354378
+5.384188208,0.8713061028,0.7587114604,-0.2194115049,1.175992693
+5.394229208,0.8999253729,0.6195459006,0.1368628532,1.101105917
+5.404270208,0.8180842343,0.1597916678,1.063310904,1.351082999
+5.414311209,0.9090680793,0.9327918412,-0.7155787432,1.486121909
+5.424352208,0.5393195437,0.8659223521,-0.8302280241,1.31528159
+5.434393208,1.103990056,0.3718297058,0.8692102414,1.453470955
+5.444434208,1.125462275,0.68368072,1.026112672,1.669428607
+5.454475208,0.9834382305,1.243070101,-0.6303310168,1.705781703
+5.464516209,1.021121489,0.6089349584,-0.0144870615,1.188991486
+5.474557208,0.967725958,0.3510389073,0.03986748576,1.030199622
+5.484598208,1.19523878,0.9205216053,0.6178507197,1.630243932
+5.494639209,1.00427968,1.129095588,-0.3386444181,1.548584698
+5.504680208,1.253979689,0.553116049,0.1125296652,1.375160118
+5.514721208,0.9045636767,0.384053968,-0.1470159584,0.9936531526
+5.524762208,1.230175674,0.8834816869,-0.09908165395,1.517790913
+5.534803208,1.028915096,0.8174812402,-0.383923502,1.369065049
+5.544844209,1.145788877,0.3326882981,0.5417632413,1.310351504
+5.554885208,1.159102257,0.8658320857,-0.3819477278,1.496351332
+5.564926208,0.742033301,0.6153800518,-0.9291886407,1.338916561
+5.574967209,1.325622114,0.616929564,0.8373148495,1.684924994
+5.585007208,1.054200576,0.8797413692,-0.2068996328,1.388557233
+5.595048208,0.7983442535,0.8471509626,-0.5454732996,1.285519125
+5.605089208,1.414183312,0.9364557065,0.2678071547,1.717144258
+5.615130208,0.8662562281,0.7822366362,0.2162013835,1.187028663
+5.625171209,1.109751464,1.036402529,0.03166618109,1.518776238
+5.635212208,1.286687113,1.09814591,0.1893234873,1.702154973
+5.645253208,0.977901502,0.9432585765,-0.04744781613,1.359514393
+5.655294209,1.282377277,1.113941725,0.2193395841,1.712736845
+5.665335208,1.149557335,1.120570494,-0.07895319879,1.60729397
+5.675376208,1.230962563,1.02830589,0.1987603086,1.616226313
+5.685417208,1.353176241,0.9598852073,0.04042472541,1.659548044
+5.695458208,1.128081754,1.147041132,-0.182280516,1.61910407
+5.705499209,1.366661528,1.016035946,-0.04603629827,1.703588013
+5.715540208,1.275460459,1.041153026,0.09828994095,1.649381678
+5.725581208,1.242573526,1.143867263,-0.3465586245,1.724100972
+5.735622208,1.352666949,1.041906806,-0.2410105348,1.724344439
+5.745663208,1.255456696,0.8604120091,0.08293339849,1.524256635
+5.755704209,1.35869382,1.087777628,-0.03888281465,1.740925311
+5.765745208,1.340044126,1.184456149,-0.429846949,1.839408336
+5.775786208,1.343056173,1.111797551,0.2786642647,1.765657795
+5.785827209,1.489724222,1.148839881,-0.0004765480757,1.881252656
+5.795868208,1.357273824,1.219552307,0.1595810401,1.831656674
+5.805909208,1.539340039,1.336110996,0.2367122465,2.052021695
+5.815950208,1.470914606,1.561603313,0.5008327317,2.202958944
+5.825990208,1.657287588,1.524303632,-0.009098267555,2.251707461
+5.836031209,1.74568521,1.334522161,0.6120222151,2.280994836
+5.846072208,1.68676121,1.478127585,0.1543366724,2.248075698
+5.856113208,1.629645315,1.669953973,-0.1862963837,2.34076835
+5.866154209,1.52625704,1.408305252,-0.1922377396,2.085602931
+5.876195208,1.536545801,1.238188553,-0.1091148913,1.976357748
+5.886236208,1.574683973,1.237388361,-0.5981175363,2.090096686
+5.896277208,1.442020151,1.094463334,-0.6534824824,1.924658791
+5.906318208,1.3429977,1.151249007,-0.5840105438,1.862816528
+5.916359209,1.314912647,1.200150953,-0.9076334649,1.998288289
+5.926400208,1.206972534,0.9000126426,-0.5163506573,1.591673162
+5.936441208,1.418157957,1.084814551,-0.2072416949,1.797482606
+5.946482208,1.222640806,1.192821614,-0.860628283,1.912682667
+5.956523208,1.182358899,1.258328702,-0.01950338781,1.726772733
+5.966564209,1.545589397,1.348139303,0.2043075621,2.061084119
+5.976605208,1.079674191,1.509073389,0.4326296389,1.905299781
+5.986646208,1.536704261,1.644829803,0.1254970354,2.25447878
+5.996687209,1.27778999,1.64687779,0.6701207346,2.189524038
+6.006728208,1.332052882,1.790473274,0.5089714712,2.288932368
+6.016769208,1.587954082,1.864160762,0.5654637605,2.513253425
+6.026810208,1.393722589,1.75547301,0.2909843481,2.260269903
+6.036851208,1.434404007,1.708561238,0.1437368399,2.235476825
+6.046891209,1.377950455,1.638217187,-0.08973780334,2.142558256
+6.056932208,1.252017656,1.554121069,-0.087174384,1.997608541
+6.066973208,1.205609109,1.56229153,-0.444925164,2.022920303
+6.077014209,1.313860294,1.537973545,-0.1654557377,2.02952386
+6.087055917,1.256399121,1.270117858,-0.43311028,1.838293404
+6.097096917,1.114239933,1.315034707,-0.4259351617,1.775462664
+6.107137917,1.321451588,1.615343318,-0.2199693292,2.098560182
+6.117178917,1.237335882,1.323297554,-0.6180126876,1.914172454
+6.127219917,1.315096541,1.258620478,0.1644102556,1.82774045
+6.137260917,1.295258839,1.439900828,-0.05532167673,1.937542346
+6.147301917,1.310622983,1.789500005,0.07298728466,2.219317466
+6.157342917,1.465703421,1.582002202,0.170003702,2.163311985
+6.167383917,1.35563061,1.450787174,0.3484566307,2.015921575
+6.177424917,1.34706707,1.577946281,0.3323387808,2.101179007
+6.187465917,1.372447641,1.668265297,-0.4934576386,2.215902089
+6.197506917,1.198731614,1.602965785,0.5584517795,2.078058032
+6.207547917,1.390119242,1.653075693,-0.05913230717,2.160691413
+6.217588917,1.333352133,1.465980872,-0.3526631176,2.012783918
+6.227629917,1.185354866,1.31732053,0.103455956,1.77513455
+6.237670917,1.141937609,1.782020977,-0.3104193234,2.139154137
+6.247710917,1.140653853,1.789694717,-0.5562222362,2.193964805
+6.257751917,1.164351814,1.358845263,0.531421271,1.86670409
+6.267792917,1.18469647,1.353017489,-0.3087984753,1.824696838
+6.277833917,1.157456996,1.967056555,0.01632367194,2.282385737
+6.287874917,1.248662962,1.748780726,-0.4387452418,2.19314628
+6.297915917,1.196769216,1.46117446,0.6935148597,2.012026396
+6.307956917,1.199182142,1.68381626,-0.5348196727,2.135253402
+6.317997917,1.030883781,1.632999278,0.5036019731,1.995751226
+6.328038917,1.711633803,1.73715266,-0.1639898407,2.444234504
+6.338079917,0.92622381,1.731107955,0.1803287154,1.97158407
+6.348120917,1.676022652,1.846210395,-0.7361714673,2.599902533
+6.358161917,0.9288108375,1.027863621,-0.4385470212,1.453105875
+6.368202917,1.2978379,1.61725945,0.8976546067,2.259578531
+6.378243917,1.664525272,1.811658321,-1.157707184,2.719013824
+6.388284917,1.243418887,1.53951224,0.194891206,1.988509755
+6.398325917,1.322092589,1.174690495,-1.045724818,2.054596546
+6.408366917,0.8947923215,1.379094755,0.4602086163,1.707146043
+6.418407917,1.693037026,1.346170546,-0.4051284295,2.200608678
+6.428448917,1.169823711,1.383386904,0.6599155891,1.928142999
+6.438488917,1.343511232,1.557493597,-0.5756080949,2.135915124
+6.448529917,1.128388075,1.512614171,-0.2360719764,1.901838914
+6.458570917,1.451484601,1.348625645,0.5115372294,2.046281754
+6.468611917,0.9956990377,1.517792026,0.4219163704,1.863631571
+6.478652917,1.532462983,1.865126576,-0.2880227333,2.431069113
+6.488693917,1.145479852,1.444176458,0.09869807661,1.845944486
+6.498734917,1.281626056,1.599976689,-0.07874620736,2.051509619
+6.508775917,1.034779634,1.890841607,-0.07971158266,2.156943396
+6.518816917,1.422858826,1.798213379,0.1592442405,2.298577239
+6.528857917,1.101112276,1.475944673,-0.244865604,1.857638309
+6.538898917,0.8926454432,1.717359543,-0.08746323645,1.937469872
+6.548939917,1.224522221,1.742610013,-0.411772036,2.169262671
+6.558980917,0.8773118511,1.733511453,0.1029197663,1.945592588
+6.569021917,1.226965699,2.02541513,-0.05285707533,2.368658934
+6.579062917,0.6831475271,2.193220132,-0.1966599888,2.305554216
+6.589103917,0.949728886,1.68716496,0.2175678778,1.948293186
+6.599144917,0.9185197379,1.894370256,0.006547712088,2.10531709
+6.609184917,0.9330860292,2.140096716,-0.3240626317,2.35704902
+6.619225917,0.8717556806,1.984927693,0.09944768965,2.170204081
+6.629266917,1.109690214,2.235990468,0.4641531479,2.538996631
+6.639307917,0.7431871028,1.991870092,-0.4782730043,2.179132534
+6.649348917,1.054097008,2.1556354,0.5458118534,2.460852506
+6.659389917,0.8285343781,2.018305354,-0.6954918033,2.289920209
+6.669430917,0.8788623865,1.679023589,0.890400551,2.09387976
+6.679471917,1.442309588,1.901629574,0.292903989,2.404629854
+6.689512917,0.5986563572,2.184209573,0.08445192039,2.266339123
+6.699553917,1.276493662,1.887825029,-0.4919484723,2.331380001
+6.709594917,0.8107190815,1.434753963,0.6860672611,1.785069368
+6.719635917,1.136174593,1.625313259,-0.4559886807,2.034812417
+6.729676917,0.9721024527,2.020591323,0.236240961,2.25468008
+6.739717917,1.120836908,1.796729794,-0.4626124066,2.167607798
+6.749758917,1.195250036,1.903388417,0.07468940914,2.24879715
+6.759799917,1.016157276,1.879120571,-0.9172550583,2.324871302
+6.769840917,1.134645327,1.841314229,0.1675876325,2.169318723
+6.779880917,1.124427756,1.770292047,-0.2591544449,2.113157055
+6.789921917,0.9268977016,1.746110449,-0.6131665152,2.069786033
+6.799962917,1.106262284,1.831126625,-0.1354963589,2.143641813
+6.810003917,0.9412093467,2.084784395,-0.484411996,2.338130875
+6.820044917,0.9258111428,1.818826715,-0.2787589896,2.059845495
+6.830085917,0.8087828491,1.451584881,-0.2049940252,1.674291167
+6.840126917,0.6625693479,1.989694928,-0.09811510921,2.099407207
+6.850167917,0.9079992083,2.515528599,-1.173941393,2.920699418
+6.860208917,0.9901586547,1.177657957,-0.5138433713,1.622136688
+6.870249917,1.056030828,1.301335266,0.5974106079,1.779206008
+6.880290917,0.9107295656,2.25923622,-0.9221100014,2.604585091
+6.890331917,1.078290886,2.017479142,0.3851023006,2.319749363
+6.900372917,1.609153748,1.277498652,1.226623637,2.392902868
+6.910413917,1.251192614,1.813395821,0.7566010541,2.329448972
+6.920454917,1.566362654,2.015588737,-0.5880866379,2.619529694
+6.930495917,1.422661628,1.656512686,0.06937078178,2.184676794
+6.940535917,0.7815277344,1.209945624,-0.303960489,1.472122954
+6.950576917,1.481563555,1.912104276,0.1027917123,2.421102944
+6.960617917,1.426530877,1.228125348,-1.67763166,2.521453985
+6.970658917,1.430963651,1.05376474,1.353148028,2.233626353
+6.980699917,1.571940898,1.601376951,-0.4492328078,2.288496546
+6.990740917,1.222827771,1.55125301,-0.4511910403,2.026145852
+7.000781917,1.577298117,0.9906025314,1.556874377,2.427554438
+7.010822917,1.351502329,1.759794103,0.0308177501,2.219095213
+7.020863917,1.233025461,1.894906738,-0.9934980726,2.469425389
+7.030904917,1.36006353,1.079271829,1.474594697,2.277944251
+7.040945917,1.361443181,1.418539926,0.6266355765,2.063602481
+7.050986917,1.217558479,1.883010724,-1.297035223,2.590459111
+7.061027917,1.217918449,1.477493747,1.263717204,2.294187065
+7.071068917,1.329431137,1.603753259,-0.1112923944,2.086096273
+7.081109917,1.092658006,2.143783678,-0.478773526,2.453351599
+7.091149542,1.284928125,1.715027527,0.09633229315,2.145143262
+7.101190542,1.127131143,1.209002249,-0.4169503301,1.704687253
+7.111231542,1.413467028,2.022387003,-0.5470169646,2.527284271
+7.121272542,0.9343349214,2.055490868,-0.7291992474,2.372710685
+7.131313542,1.32648414,1.581321293,-0.5390986651,2.133252113
+7.141354542,1.055070642,1.568147955,-0.6411922199,1.995843063
+7.151395542,1.401458016,2.051098732,-0.8627198321,2.629710267
+7.161436542,1.214321022,1.470840785,-0.4600910872,1.962047902
+7.171477542,1.227187601,1.944953495,-0.03605451643,2.300029007
+7.181518542,1.260418351,2.394718546,-1.124608435,2.930541838
+7.191559542,1.062769963,1.603965659,-0.1547833997,1.930322183
+7.201600542,1.273535264,1.109116091,1.944768723,2.575685532
+7.211641542,1.25313462,1.998242534,0.05480361342,2.359305626
+7.221682542,1.063667292,1.87413392,0.201806708,2.164368731
+7.231723542,1.494273794,1.457938904,1.907155924,2.827664007
+7.241763542,0.9202872781,1.482304105,0.2980799443,1.770029883
+7.251804542,1.118710568,1.601465828,1.284449676,2.337951476
+7.261845542,1.173075275,1.542609656,0.7055671406,2.06241973
+7.271886542,0.5319984642,1.887582077,-0.175854426,1.968987873
+7.281927542,1.730093609,2.470531059,0.9235875928,3.154324278
+7.291968542,0.8030671227,1.671566197,-0.8669456148,2.047106507
+7.302009542,1.039282283,1.780119463,0.9727907431,2.279310158
+7.312050542,1.074140167,2.598351193,-1.460920399,3.168516125
+7.322091542,0.4125811079,2.183507469,-0.890553748,2.393953637
+7.332132542,1.786650364,1.857402112,0.3695685875,2.603582737
+7.342173542,0.6380462717,1.993240533,-0.8549757797,2.260772976
+7.352214542,1.197109378,2.514434585,-0.9939997637,2.956938903
+7.362255542,0.9333475459,2.402468884,-0.8463511366,2.712803831
+7.372296542,0.8975155161,1.588590406,-0.7483056092,1.972083889
+7.382337542,1.412376668,2.374619034,0.6823414153,2.845911667
+7.392377542,0.5934971761,2.27888228,-1.671018459,2.887532863
+7.402418542,1.292685187,2.135593191,1.01384229,2.694377379
+7.412459542,1.101398351,2.01084723,-0.07236338675,2.293866032
+7.422500542,0.4686067528,1.795049743,-0.7076119119,1.985575606
+7.432541542,1.77542064,2.119969723,0.9379103476,2.91994279
+7.442582542,0.1020716277,1.571435844,-0.560811131,1.671627457
+7.452623542,1.562764131,1.996126134,1.581489401,2.987952476
+7.462664542,0.3555465259,2.167045949,-0.6756907922,2.297620404
+7.472705542,0.5938003908,2.44313583,1.442278306,2.898564869
+7.482746542,1.163130476,2.738243781,0.3835562968,2.999661138
+7.492787542,0.5129932592,2.169984613,1.092891383,2.483225096
+7.502828542,1.308361426,2.319061422,0.325706284,2.682524946
+7.512869542,-0.1835190659,2.441430344,-0.5660250932,2.512895895
+7.522909542,1.104242291,2.730755837,0.7106904709,3.030092312
+7.532950542,0.2513892695,2.104521087,-1.330090703,2.50226834
+7.542991542,0.6864729117,2.24048917,0.4246265548,2.381458479
+7.553032542,0.7300723828,2.535395099,-1.724053289,3.151760419
+7.563073542,0.6720066078,2.403327986,-0.1935457617,2.503005843
+7.573114542,1.091770472,2.513096158,-0.2546614444,2.751811678
+7.583155542,0.4064908308,2.313962066,-1.333118976,2.701270338
+7.593196542,1.214503675,2.273964333,-0.6249913394,2.652649079
+7.603237542,0.2912823733,2.081662859,-1.458947548,2.558650744
+7.613278542,1.211078083,2.281287971,0.820190109,2.709925598
+7.623319542,0.8674929873,2.210374694,-0.5155314624,2.429829841
+7.633360542,0.6374536563,2.292800261,0.7853804648,2.506013303
+7.643401542,1.009683166,2.73389433,-1.532461667,3.292730943
+7.653442542,0.1554000982,1.91788001,0.6772169155,2.03986168
+7.663482542,1.052033745,2.13495102,0.07319778442,2.381207419
+7.673523542,0.09977051991,2.689176579,-0.6468447232,2.767676448
+7.683564542,0.8361539579,1.947430376,-0.7113020897,2.235528835
+7.693605542,0.7773258521,1.701699822,0.4777426618,1.930869187
+7.703646542,0.4959383199,2.500170303,-0.6111603355,2.62113016
+7.713687542,0.5645764455,2.568827432,-0.8450928158,2.762571774
+7.723728542,0.6317523287,2.051976545,1.139576138,2.430710291
+7.733769542,-0.1343914727,2.382856884,-0.2683491915,2.401682595
+7.743810542,0.9088946363,3.100647483,0.2004191637,3.237324839
+7.753851542,0.8655476186,2.353208723,0.1066350871,2.509608539
+7.763892542,0.6958823242,1.818058391,1.150062534,2.261024625
+7.773933542,0.4632128426,2.540198587,0.1627917463,2.587213975
+7.783974542,0.7834372158,2.721936189,-1.03284808,3.014877385
+7.794014542,0.3310793271,2.034635312,-0.3235890073,2.086639456
+7.804055542,1.024407039,2.154066299,0.667331028,2.476841154
+7.814096542,0.5557965954,1.937596236,-1.526978733,2.528804674
+7.824137542,0.5968438666,2.248906968,0.3765174186,2.357025778
+7.834178542,0.08762530482,2.409942064,-1.612569106,2.901013283
+7.844219542,0.7321212472,2.12977872,0.9166258979,2.43149377
+7.854260542,0.9822075377,2.012922992,-0.620260942,2.324072773
+7.864301542,0.2151792536,2.070186237,0.8459552801,2.246689454
+7.874342542,0.9821625873,2.198893247,-1.557678954,2.868124576
+7.884383542,0.3550947919,1.771323935,1.143820047,2.138224753
+7.894424542,0.9578185089,1.578172714,-0.5153595543,1.916674433
+7.904465542,0.6780937786,1.688672518,0.9556730193,2.055416495
+7.914505542,1.504061156,1.706911884,-0.761322096,2.399033029
+7.924546542,0.5161228717,1.529171,0.5735264862,1.712798703
+7.934587542,0.8908151186,2.143811891,0.159171735,2.326975857
+7.944628542,0.7094116118,3.025712491,0.9719347107,3.256203002
+7.954669542,1.30194016,2.42884772,-0.6466377318,2.830634167
+7.964710542,1.410307923,1.508631486,1.513641819,2.560478267
+7.974751542,0.8489774135,1.576816891,-1.541832415,2.363125336
+7.984792542,0.2168120521,2.588491618,-0.07033498764,2.598507905
+7.994833542,1.079941555,2.593887721,-0.5951225924,2.872054695
+8.004874542,0.5750494666,1.331705558,0.0332338196,1.450939719
+8.014915542,0.4863799861,1.820551205,0.4847949886,1.94576421
+8.024956542,0.956659006,2.28242847,-1.80895603,3.065452347
+8.034997542,0.5490458753,1.348499053,-0.4256533259,1.516931714
+8.045037542,0.8055548206,1.313324689,1.228347396,1.970425749
+8.055078542,0.3695755677,2.061267186,-0.4905872405,2.150833409
+8.065119542,1.190393997,1.792507666,-0.4378886247,2.195875235
+8.075160542,0.859115316,1.213395627,0.7133088541,1.649005032
+8.085201542,1.346101549,1.65674789,-0.7131790459,2.250650418
+8.095243208,1.194018247,1.668524329,0.04732853293,2.052289697
+8.105284208,1.252935377,1.122267941,0.07640264332,1.683796233
+8.115325209,1.097096408,1.524915104,0.2241284537,1.891882705
+8.125366208,1.475478065,1.434622254,-1.451591166,2.518391043
+8.135407208,1.237526794,0.650923887,0.8230640155,1.622531616
+8.145448209,1.352483492,1.30388626,0.3270949978,1.906914291
+8.155488208,0.478662977,1.910519242,-0.4114019072,2.012076924
+8.165529208,1.552164299,1.367211898,0.2467981088,2.083120661
+8.175570208,0.4786162359,0.3111686441,0.4566745591,0.7310616111
+8.185611208,1.068896091,1.383571384,0.8490736002,1.943639526
+8.195652209,1.088322223,1.869538739,-0.5030716306,2.220968578
+8.205693208,1.055785464,0.8277119672,0.7495306009,1.536745317
+8.215734208,1.033918193,0.481899886,-0.5131282568,1.250805716
+8.225775208,0.9560389088,1.433871618,-0.01701013505,1.72345222
+8.235816208,1.267450505,1.741132129,-1.122181841,2.428428289
+8.245857209,1.328596301,0.8914302456,0.3910266995,1.647033058
+8.255898208,1.48702734,0.7962400599,-0.6343965858,1.80213972
+8.265939208,1.135938,1.482463442,-0.6781097853,1.986928755
+8.275979209,1.371435488,1.477641243,-0.8170343667,2.17527104
+8.286020208,1.383470665,0.5179867083,0.2282267672,1.494787199
+8.296061208,1.428787464,0.7444847462,0.3409634238,1.64679908
+8.306102208,1.115778774,1.177269921,-1.194863901,2.014603306
+8.316143208,1.454712849,1.279343595,-0.1733354455,1.944981924
+8.326184209,1.132797607,0.3242167424,-0.08200836897,1.181131782
+8.336225208,1.221112709,0.2778430963,0.2545304668,1.277927539
+8.346266208,1.309280024,1.053360039,-0.3206917119,1.710738065
+8.356307209,0.9492160121,1.046349812,-0.9631428373,1.709825457
+8.366348208,1.099706605,0.5205190277,0.5153823584,1.321330258
+8.376389208,1.284565013,0.7808943348,-0.5014776796,1.584734393
+8.386430208,0.6437389015,1.169518267,-0.4287155128,1.40213043
+8.396470208,1.151989996,1.008521909,-0.08546875119,1.533460889
+8.406511209,1.135858186,0.7905001406,0.7757050771,1.586437095
+8.416552208,0.7334333624,1.063892921,0.03444360852,1.292663532
+8.426593208,0.7105212671,1.615966485,-0.1372417527,1.770599743
+8.436634209,0.4079246777,0.7998115392,0.0953873831,0.902884153
+8.446675208,0.893819418,1.10148891,1.028728716,1.752276731
+8.456716208,0.742490334,1.529349633,0.1625210202,1.707810082
+8.466757208,0.7356958694,1.197534251,0.643178519,1.545643976
+8.476798208,1.011477822,1.137643487,0.4887208092,1.598802088
+8.486839209,0.3687139073,1.095194748,-0.4095161802,1.22601182
+8.496880208,1.116460559,1.291364594,0.1524778426,1.713871695
+8.506920208,0.5484618846,0.9961494926,-0.1413119996,1.145902846
+8.516961209,0.6409915873,1.12737563,-0.09636737645,1.30043558
+8.527002208,1.005539317,1.410747488,0.1280984616,1.737160617
+8.537043208,0.8188235416,1.12837068,-0.2604624671,1.41828526
+8.547084208,0.8128202053,0.9978725208,1.491307794,1.969879486
+8.557125208,0.5272028703,0.7519732022,0.3799549967,0.9938673768
+8.567166209,0.7769495107,1.211596878,0.2068739051,1.454102592
+8.577207208,0.4387111817,1.063645438,0.1759000343,1.163937258
+8.587248208,1.216151347,0.7455711588,0.4338166237,1.491005471
+8.597289209,0.8317556092,0.9966881673,0.7100168717,1.479638015
+8.607330208,0.6579176686,1.386441197,-0.3461604291,1.573182092
+8.617370208,0.9251818362,1.400786317,-0.3157280105,1.708170926
+8.627411208,0.8268457022,0.5343513107,-0.1119607311,0.9908281102
+8.637452208,0.9053335357,0.4729085859,0.2811966938,1.059406873
+8.647493209,0.8638678598,1.080767182,-0.5822809374,1.501125068
+8.657534208,0.6249838842,1.337182498,-1.458240035,2.074879729
+8.667575208,0.8512027176,1.419760678,-0.05965797186,1.656449674
+8.677616208,0.7743213335,1.067725771,-0.08313805103,1.321561117
+8.687657208,0.4813806532,1.130905155,-1.191762537,1.712008104
+8.697698209,0.6221914733,1.21894712,0.4561716986,1.442583422
+8.707739208,0.3691652028,1.314541348,-0.6735624057,1.522494078
+8.717780208,0.3326104205,1.770444514,-0.2065669262,1.813221818
+8.727820209,0.6726313828,1.188773441,0.1486104941,1.373936079
+8.737861208,0.4868649395,0.7716859934,1.146730206,1.46544427
+8.747902208,0.7078448503,1.711904822,-0.01292000771,1.852519737
+8.757943208,0.1796125412,1.194055158,-0.02493779004,1.207745949
+8.767984208,1.041375659,1.245202726,0.4446409893,1.683062299
+8.778025209,0.1518366223,1.507367318,-0.9185911471,1.771728051
+8.788066208,0.719014421,0.9550529221,-0.1783967954,1.208690712
+8.798107208,1.000198982,1.006229069,0.1205058521,1.423873802
+8.808148209,0.3255766951,1.589648313,-1.295492728,2.076363011
+8.818189208,0.9911170133,1.726154486,-0.5060806078,2.053786704
+8.828229208,0.7399831941,0.8349135442,-0.2313193595,1.139370177
+8.838270208,0.9218234879,1.211224995,-0.819089663,1.728505831
+8.848311208,0.3990976844,1.878400194,-0.9793466413,2.15564053
+8.858352209,0.7406406404,1.467411393,-0.8275400591,1.840290005
+8.868393208,0.5449328707,1.210404923,-0.0703501904,1.329278398
+8.878434208,0.5804004363,1.432823212,0.2469056976,1.565506131
+8.888475209,0.5213666913,1.363751077,-0.1388199162,1.466598512
+8.898516208,0.4283333241,1.182712509,0.6436544824,1.413000145
+8.908557208,0.4104748677,1.184425013,0.361852017,1.304718019
+8.918598208,0.2941521868,0.8905306515,0.4237629211,1.029147882
+8.928639208,0.6732444634,1.184188639,0.2213182819,1.380051674
+8.938679209,0.3376253581,1.47591149,-0.2613693702,1.536430785
+8.948720208,0.63540238,1.009041726,-0.1417025936,1.200825139
+8.958761208,0.8117263374,0.9290415832,0.6572901893,1.397872778
+8.968802209,0.3551810383,0.9572809305,-0.5206863678,1.146147741
+8.978843208,0.5314486067,1.118896948,0.536417132,1.349856045
+8.988884208,0.6901502987,0.9980859442,0.03627846479,1.214001282
+8.998925208,0.3914906761,0.6752567826,0.1297964931,0.7912545744
+9.008966208,0.733927379,1.069938065,1.15909122,1.739801516
+9.019007209,0.6447615796,0.8649974687,-0.3180306441,1.124758466
+9.029048208,0.4276927616,0.2443555441,0.8949257112,1.021529617
+9.039088208,0.9841493981,0.5384787872,0.8535227466,1.409613607
+9.049129209,0.2273200102,0.8896820012,-0.6745979476,1.139425663
+9.059170208,0.8396471576,1.256284662,-0.315153814,1.543560957
+9.069211208,1.119881984,1.077138984,-0.6562745279,1.686730656
+9.079252208,0.2974035128,1.011825001,-0.9905586773,1.446874277
+9.089293208,0.8654990868,1.359757282,-0.6195124984,1.726795955
+9.099334209,0.5067167117,1.413970619,-0.5613022971,1.603475914
+9.109375208,0.4532421339,1.169395476,0.02947522938,1.254505082
+9.119416208,0.638231336,1.298347923,-0.1575263286,1.455287295
+9.129456209,0.3676005975,1.373640619,-0.685519377,1.578592907
+9.139497208,0.7713057782,1.14781121,0.7932514018,1.594249342
+9.149538208,0.2352875176,0.739241621,0.9666073126,1.239422481
+9.159579208,0.4167581029,1.313235811,0.1281820768,1.383729113
+9.169620208,0.4330223891,1.290874597,0.3299706584,1.40098046
+9.179661209,0.1423064648,0.4416644642,0.6349392074,0.786426364
+9.189702208,0.5093644041,0.4875605755,1.443003361,1.606059186
+9.199743208,0.2883143632,1.388925387,0.1988065016,1.432397615
+9.209784208,0.3402525852,1.097555926,-0.0653584224,1.150944202
+9.219825208,0.5969445483,0.5880895249,1.233229821,1.490988892
+9.229865209,0.2970048788,1.257832858,-0.7592627066,1.498944714
+9.239906208,0.1103066269,1.215768208,-0.6852702856,1.399948303
+9.249947208,0.9813879043,0.9052866849,0.436499911,1.404705796
+9.259988209,-0.04251384877,0.9633278286,-0.8403314281,1.279048413
+9.270029208,0.3030929815,1.67886893,-0.291700632,1.730767315
+9.280070208,0.9069851549,0.8918261752,0.3421036309,1.317198122
+9.290111208,0.062603155,0.1227493374,0.09482838929,0.167269179
+9.300152208,1.020494083,1.231424201,1.440031221,2.152092854
+9.310193209,0.3588675616,1.202623375,-1.121231083,1.682928415
+9.320234208,0.637031195,0.7307440086,-0.268556183,1.005941337
+9.330274208,0.7807233768,0.4453679444,0.5901577216,1.075252404
+9.340315209,0.3154044402,0.6740254321,-0.7391482848,1.048871027
+9.350356208,0.360657906,1.07600097,-0.1892615068,1.150509509
+9.360397208,0.6402469444,0.7391886306,0.6208246136,1.158334659
+9.370438208,0.5256399461,1.153344576,0.2449100429,1.290922923
+9.380479208,0.4748453665,1.126321377,-1.057309322,1.61616242
+9.390520209,0.1526080528,0.5212568002,0.09648022771,0.5516396504
+9.400561208,0.8286929107,0.9471190544,0.5952366132,1.392146928
+9.410602208,0.1076475782,1.352043782,-0.167145583,1.366582612
+9.420642209,0.2303765143,1.561814543,-0.2420513391,1.597162126
+9.430683208,0.705786265,0.8547201101,0.7894208908,1.360832856
+9.440724208,0.2009365327,0.9362886223,-0.8536151326,1.282836961
+9.450765208,0.2249737601,1.494616733,-0.5182042247,1.597819762
+9.460806208,0.1679999709,1.510376441,-0.04764720619,1.520437845
+9.470847209,0.4986315108,1.548490639,-0.2772281885,1.650246076
+9.480888208,0.05381772718,1.65802463,-1.214533349,2.055975019
+9.490929208,0.2346771962,1.50765924,-0.5959581596,1.638070786
+9.500970209,0.4832753338,1.235462727,-0.1263466358,1.332623979
+9.511010208,0.21703812,1.418708033,-0.6903737354,1.592624854
+9.521051208,-0.06839189393,2.034598182,0.02054009914,2.035850954
+9.531092208,0.4704060142,1.561800949,-0.3439759094,1.666980338
+9.541133208,0.1594609712,0.7724486165,0.4632561851,0.9147190604
+9.551174209,0.3187741175,1.265971744,0.100417158,1.309345256
+9.561215208,-0.1443765618,1.862636393,-0.4826326883,1.929557783
+9.571256208,0.3686979737,1.692290922,0.2384974015,1.748332854
+9.581297209,0.2190242365,0.9760059077,0.3307559395,1.053545746
+9.591338208,0.4277158216,0.9632407781,0.7165762782,1.274462704
+9.601378208,0.6643749681,1.04817619,-0.2587392926,1.26768034
+9.611419208,0.3882816511,1.035491094,-0.2826462185,1.14144353
+9.621460208,0.5111915128,0.8332263301,0.6784208572,1.189889801
+9.631501209,0.2408489872,0.6620473377,-0.6759322822,0.9763192931
+9.641542208,0.6015964103,0.6780480972,-0.5413065737,1.055784197
+9.651583208,0.7252300843,0.6310709819,0.4814918965,1.075194729
+9.661624208,0.9802739366,0.7553081616,0.3034529507,1.274170751
+9.671665208,0.7755913487,0.4559504545,-1.247172507,1.537814039
+9.681706209,0.8832280639,0.2821548697,0.05536728501,0.9288534435
+9.691746208,0.9456392703,0.1159157878,-1.389176817,1.684482807
+9.701787208,0.6853923462,0.4057284635,0.01067818522,0.7965502357
+9.711828209,0.7281368083,0.6386622758,-1.271218012,1.598145159
+9.721869208,0.9479033853,0.7093182756,-0.8852473998,1.478281503
+9.731910208,0.8550824913,0.359645424,-0.556600551,1.081811015
+9.741951208,0.479044654,0.4861683534,-1.560089176,1.702856919
+9.751992208,0.5728023085,1.040812865,-0.1701744407,1.200147176
+9.762033209,0.9107011335,0.5999684724,-0.7981215477,1.351420263
+9.772074208,0.4055121531,0.3060315545,0.01483380139,0.5082474401
+9.782114208,0.3400351784,0.6743707833,-0.1506979501,0.770136188
+9.792155209,0.6944680289,0.2707248604,-0.4723562068,0.882438768
+9.802196208,0.7812005096,-0.267348806,0.8438672394,1.180619133
+9.812237208,0.642040797,0.4920739681,0.04138717711,0.8099790575
+9.822278208,0.1881932205,0.75586679,-0.4564944649,0.9028502029
+9.832319208,0.7516097246,0.02278162926,1.322865298,1.521646732
+9.842360209,0.423689502,-0.5162574673,0.06024795592,0.6705701924
+9.852401208,0.7621591249,0.09418853944,0.3995975482,0.8656998401
+9.862442208,0.9094698561,0.5795399089,-0.7342956805,1.304680831
+9.872482209,0.4945613371,-0.4113568836,0.3701112092,0.742150732
+9.882523208,1.087619387,-0.3999443978,0.1259414238,1.1656469
+9.892564208,0.5434150066,0.6940501723,-0.231963138,0.9114891159
+9.902605208,0.557883759,0.4840431098,-0.4926068687,0.8878026514
+9.912646208,0.8880183222,-0.6766871578,1.34313701,1.7465678
+9.922687209,0.8155186222,-0.005205136556,-0.1334358001,0.8263793496
+9.932728208,0.6726541869,0.2078375262,-0.561588226,0.9005783853
+9.942769208,0.9450508942,-0.4115048913,1.067151355,1.483667578
+9.952809209,0.871345133,-0.3421796447,0.3480332923,0.9987274015
+9.962850208,0.6952182267,0.01417043477,-0.4972670996,0.8548706056
+9.972891208,0.4635390807,-0.3274279967,0.4242154956,0.7085452413
+9.982932208,0.7869933461,-0.4707758506,0.428274048,1.012129976
+9.992973208,0.6954643945,-0.7016611274,-0.2878122336,1.028997057
+10.00301421,1.03437318,-0.5292095616,-0.09617968082,1.165864986
+10.01305521,0.8442262584,-0.7150533709,0.6900310886,1.303902681
+10.02309621,0.7714756398,-0.7819276839,-0.5569823742,1.231590407
+10.03313721,0.7308402684,-1.133079004,-0.6666445649,1.504131146
+10.04317721,1.129042817,-1.098596219,-0.5011625147,1.653122864
+10.05321821,0.5489065288,-0.9781407262,-0.9486522675,1.46901286
+10.06325921,0.6478397001,-0.9492652749,-0.8770186132,1.445670255
+10.07330021,0.8529353207,-1.278703325,-0.9691321403,1.817085017
+10.08334121,0.7398925623,-1.576215797,-0.2817972028,1.763889709
+10.09338129,0.4328285173,-1.416072839,-0.4201323849,1.539192656
+10.10342229,0.1796060361,-0.989299918,-1.05482367,1.457266493
+10.11346329,0.4833962616,-1.243702038,-0.2466530979,1.356946741
+10.12350329,0.6620672914,-1.593107526,-0.009530376792,1.72522912
+10.13354429,0.4249542547,-1.630459686,-0.3130710357,1.713767306
+10.14358529,0.6076020855,-1.447468441,-0.2702203006,1.592910604
+10.15362629,0.4496459135,-1.289952491,-0.4215023875,1.429623426
+10.16366729,0.3015096651,-1.375100522,-0.234029544,1.427087717
+10.17370829,0.2980676103,-1.846132042,-0.2802026671,1.89091548
+10.18374929,0.7386806537,-1.839093749,0.6072403622,2.072837616
+10.19379029,0.506907733,-1.691702545,-0.1761333382,1.774777706
+10.20383129,-0.1285587837,-1.711116763,-0.3141901928,1.744466513
+10.21387129,0.1357444453,-1.720198805,0.1149469042,1.729370774
+10.22391229,0.05967770164,-1.134286235,0.1841007543,1.150677965
+10.23395329,-0.235819998,-0.6793477871,0.637540049,0.9610316338
+10.24399429,-0.2453815112,-0.6856227265,1.027306674,1.259225798
+10.25403529,-0.07032681067,-0.9648820185,1.030262441,1.413288317
+10.26407629,-0.09584416942,-1.460886485,0.8346163595,1.685218055
+10.27411729,-0.1614750264,-2.183182363,3.018092984,3.728437297
+10.28415829,0.07915047836,-1.873237103,0.8111099678,2.042836612
+10.29419829,-0.1174942985,-1.912015983,0.7184468025,2.04591687
+10.30423929,0.0507893537,-1.745058096,1.496989533,2.29973585
+10.31428029,0.2704007968,-1.82030226,1.839075038,2.601694429
+10.32432129,0.163325396,-2.297367522,1.572304595,2.788676111
+10.33436229,0.3521035026,-2.31238054,0.1186686569,2.342042461
+10.34440329,0.2855519375,-2.56732382,1.772690429,3.132909648
+10.35444429,-0.03274062524,-2.666988149,0.6635034406,2.748478589
+10.36448529,0.2382187086,-2.365380872,-0.559643442,2.442329954
+10.37452529,0.07543533113,-2.522720967,-0.09053945661,2.525472027
+10.38456629,0.1843654687,-2.424651466,0.0411755079,2.431999338
+10.39460729,0.06934335468,-2.805656038,0.1804708028,2.812309374
+10.40464829,0.01310408536,-2.407792774,-1.972352378,3.112524966
+10.41468929,0.2106222809,-2.517671896,0.01648739398,2.526520405
+10.42473029,0.1089441343,-2.569796608,-0.5406961244,2.628321847
+10.43477129,0.1746260539,-2.321227377,-0.7036217719,2.431804761
+10.44481229,-0.1086931426,-2.217935582,-0.7421251023,2.341324863
+10.45485229,-0.2847890038,-2.011463234,-0.5871317875,2.114666133
+10.46489329,-0.2818703478,-2.44388442,0.1239662343,2.463207173
+10.47493429,-0.1161174802,-2.377007183,0.04291154623,2.380228523
+10.48497529,-0.174009465,-2.065386111,-0.02651302993,2.072872891
+10.49501629,-0.5273370274,-2.422667067,0.1988199502,2.487353902
+10.50505729,-0.5135261598,-2.539588722,0.321733101,2.610887241
+10.51509829,-0.3802862415,-2.362146485,-0.3128716457,2.412932305
+10.52513929,-0.380042778,-2.316232393,0.07780071259,2.3484927
+10.53517929,0.1082294767,-2.174584179,-0.1187551957,2.180512042
+10.54522029,0.07996960932,-2.307057527,0.2453041452,2.321440005
+10.55526129,-0.05171283005,-2.245234331,-0.3866985905,2.2788785
+10.56530229,-0.044183206,-2.084678707,-1.017993228,2.320376624
+10.57534329,-0.1676914206,-2.191735817,0.3026676697,2.218881254
+10.58538429,0.2594968908,-2.297123108,0.9185969943,2.487555758
+10.59542529,-0.1079325295,-1.910039771,-1.409100035,2.376018574
+10.60546629,-0.6793461791,-2.300779664,-0.1125331736,2.401616541
+10.61550629,-0.6040080944,-2.633606395,1.051735171,2.899457758
+10.62554729,-0.2744509804,-2.153410973,-1.212623064,2.486555218
+10.63558829,-0.3876167496,-2.394337892,0.2322636849,2.436605652
+10.64562929,0.2457784458,-2.359174345,0.7669547188,2.492855827
+10.65567029,0.2159854385,-2.079737663,-0.9297897345,2.288332888
+10.66571129,-0.01327716295,-1.899590796,-1.63286947,2.504971892
+10.67575229,-0.1031914243,-2.721279547,1.418840911,3.07068728
+10.68579229,-0.2318605376,-2.791784396,-1.062340851,2.996062
+10.69583329,-0.1568370697,-2.361521417,-0.274847787,2.382629341
+10.70587429,-0.06954342082,-2.204635505,-0.5412673974,2.271172471
+10.71591529,0.04782834196,-2.247114211,0.8350069535,2.397716923
+10.72595629,0.02648160115,-2.281808081,-0.1491794282,2.286832721
+10.73599729,-0.3146061126,-2.474251642,-1.027791992,2.697638704
+10.74603829,-0.2731015526,-2.329948353,-0.5714133024,2.414488962
+10.75607929,-0.4253231775,-2.622573284,0.3403056121,2.678544072
+10.76611929,-0.312868649,-2.385357592,-1.166189155,2.673539747
+10.77616029,-0.5059452447,-2.455711291,-0.3464849496,2.531116425
+10.78620129,-0.3856403541,-2.749866292,1.06129186,2.972679518
+10.79624229,-0.0985152963,-2.788723086,0.3638915259,2.81408933
+10.80628329,-0.1558891082,-2.62845149,0.04069252789,2.633384615
+10.81632429,-0.5104419728,-2.952379636,-0.0372952956,2.996412431
+10.82636529,-0.4882393641,-2.857241344,0.7738532639,3.000175769
+10.83640629,-0.2398954159,-2.804777201,0.8063316232,2.928223975
+10.84644629,-0.7270614322,-3.063531697,-0.08422738731,3.149752218
+10.85648729,-0.5483474985,-2.671519449,-0.4110154063,2.758012837
+10.86652829,-0.3497743373,-2.607574883,0.8032419544,2.750815606
+10.87656929,-0.646220606,-3.102185885,-0.006626649499,3.168785611
+10.88661029,-0.2718834314,-2.657586996,-0.303364073,2.688627717
+10.89665129,-0.2395564601,-2.518980503,0.01703410864,2.530403176
+10.90669229,-0.5534926828,-2.986341434,0.6398637325,3.103870955
+10.91673329,-0.4737843161,-2.772697037,-1.586105193,3.229249158
+10.92677329,-0.2973848748,-2.851382141,-0.5825247663,2.925432102
+10.93681429,-4.593972274,-5.210729272,-0.3933772802,6.95780328
+10.94685529,-2.094042876,-4.115513036,0.9306761724,4.710479939
+10.95689629,-0.3004795502,-4.181577217,0.2398399222,4.199214113
+10.96693729,0.09726547223,-3.951583714,-0.253101992,3.960875539
+10.97697829,-1.516223364,-3.946595454,-1.061645617,4.359087104
+10.98701929,-1.541514034,-3.747166224,0.06697342336,4.052407391
+10.99705929,-1.388185714,-3.552539604,-0.8378329128,3.905068656
+11.00710029,-2.053842099,-3.492127342,0.2310807931,4.057908214
+11.01714129,-1.369243659,-3.095107246,0.8446800023,3.488266241
+11.02718229,-1.221277089,-2.825234562,0.7555772066,3.169284616
+11.03722329,-1.499462613,-3.009417762,-0.53824848,3.405098357
+11.04726429,-0.9959099029,-3.455513539,0.8956566131,3.706023627
+11.05730529,-1.210625801,-3.58539394,1.229823818,3.979086724
+11.06734629,-1.477671064,-3.13137197,0.7095286292,3.534463617
+11.07738629,-1.610207123,-2.733418659,0.2198681724,3.180045056
+11.08742729,-1.076318327,-2.86971784,-0.83119223,3.17562941
+11.09746846,-1.165477037,-3.360736605,-0.08673818171,3.558147097
+11.10750946,-1.065354944,-2.874250017,0.1981521982,3.07173544
+11.11755046,-1.400480654,-2.179481368,-1.292291962,2.895082661
+11.12759146,-1.753338923,-3.255356623,-0.84307845,3.792403643
+11.13763246,-1.296266461,-3.499667911,0.1558575332,3.73527426
+11.14767246,-1.605119023,-3.337151569,-0.3011690283,3.715331809
+11.15771346,-2.192334718,-2.747200838,-1.189121935,3.71045212
+11.16775446,-1.53112894,-2.962933567,-0.4120088482,3.360518182
+11.17779546,-1.528686266,-3.27464191,-0.1929452527,3.619031529
+11.18783646,-2.308459251,-3.616493526,-0.3240912831,4.302678781
+11.19787746,-2.322970579,-3.319664885,-0.1729512835,4.055401263
+11.20791846,-1.653397874,-3.166107354,0.7938975191,3.65899352
+11.21795846,-1.975884097,-3.532041313,0.2743320626,4.056438324
+11.22799946,-1.649067719,-3.72878287,0.691391151,4.135367911
+11.23804046,-1.669004093,-3.401201384,0.8071987653,3.873669496
+11.24808146,-1.52318886,-3.654639299,0.4572189349,3.985667053
+11.25812246,-1.952638783,-3.468663927,0.8711795837,4.074724717
+11.26816346,-0.9785196988,-3.075875754,0.06864280343,3.228501864
+11.27820446,-1.719902643,-3.600274811,-0.1813478851,3.994112026
+11.28824546,-0.9555307127,-3.088482935,0.3744206071,3.254528626
+11.29828546,-1.434457509,-3.14412884,-0.276935243,3.466973844
+11.30832646,-2.031119673,-3.608995641,0.2189098138,4.147073446
+11.31836746,-1.577146089,-3.668139642,-0.1745148289,3.996635291
+11.32840846,-2.087753173,-3.068302148,-0.2968836039,3.723080882
+11.33844946,-1.789903463,-2.973910253,-0.7363626713,3.548256837
+11.34849046,-1.655886157,-3.527427567,0.1788938087,3.900859803
+11.35853146,-1.799625628,-3.714639917,-0.232137385,4.134137139
+11.36857146,-2.118252396,-3.016853959,-0.7535031992,3.762468351
+11.37861246,-2.375497725,-2.819155505,-1.137892724,3.858163689
+11.38865346,-2.09255476,-3.676062035,-0.3749012482,4.246500731
+11.39869446,-1.40270245,-3.705062178,0.5243046248,3.996242641
+11.40873546,-1.900827044,-3.028981084,-0.2898225063,3.587738416
+11.41877646,-2.042190499,-3.279020597,-1.103414032,4.017466943
+11.42881746,-1.429214603,-3.561622377,0.7858996975,3.91732647
+11.43885746,-1.736915263,-3.431004058,0.1803866029,3.849831529
+11.44889846,-1.824048717,-3.444083402,-0.7084135652,3.961150588
+11.45893946,-1.614640336,-3.754593065,1.114726056,4.236348271
+11.46898046,-1.864929964,-3.301907184,0.8150083065,3.878761833
+11.47902146,-1.947637075,-3.08829407,0.218617453,3.657682877
+11.48906246,-2.088083833,-3.616247942,0.0690567863,4.176375476
+11.49910346,-1.653982157,-3.787551481,1.267720208,4.322998695
+11.50914346,-2.624476553,-3.477490591,-0.1418324018,4.359006127
+11.51918446,-2.394968514,-2.90625329,-1.321918634,3.991196719
+11.52922546,-1.903054541,-3.404990087,0.5772692889,3.943198437
+11.53926646,-2.144555657,-3.334003135,-0.2471664834,3.971874512
+11.54930746,-2.108190653,-2.765777442,-1.503234944,3.788628774
+11.55934846,-2.352563191,-3.12298297,-0.7228901017,3.976197467
+11.56938946,-1.892211025,-3.207418518,0.6410033548,3.778740718
+11.57942946,-2.33775424,-3.127127768,-1.194448164,4.082980453
+11.58947046,-2.538171065,-2.845944231,-0.5697725737,3.855690821
+11.59951146,-1.51541411,-2.964278135,-0.5097661078,3.367979553
+11.60955246,-1.889064785,-3.595830635,0.5317972469,4.096507296
+11.61959346,-1.981659976,-3.288428767,-1.178906264,4.016286842
+11.62963446,-1.899540949,-2.84862401,0.1946380216,3.429402065
+11.63967546,-2.014017298,-2.701499001,-0.8650306517,3.478884959
+11.64971546,-2.202740569,-3.627035178,-0.4073848701,4.263028575
+11.65975646,-1.438596607,-3.341049615,0.3156864953,3.651277953
+11.66979746,-1.673006073,-3.038347739,-0.2935530299,3.480902137
+11.67983846,-2.109236282,-2.584031947,-0.4872022873,3.370973874
+11.68987946,-1.997259617,-2.863830864,-0.350003804,3.508999267
+11.69992046,-1.878370374,-2.957650023,-0.2619903445,3.513489414
+11.70996146,-2.326006745,-2.774933305,0.05167769194,3.621219796
+11.72000146,-2.093784429,-3.23950833,-0.5888584703,3.901935642
+11.73004246,-1.917538678,-3.438980537,1.044268861,4.073578178
+11.74008346,-1.870310279,-2.990821278,0.5777908605,3.574481044
+11.75012446,-2.234546206,-2.415492972,-0.5015934545,3.328573124
+11.76016546,-2.209461066,-2.996380518,0.118899622,3.724802214
+11.77020646,-1.459551566,-3.320905957,0.7491581333,3.704044419
+11.78024746,-2.313492534,-3.293156533,0.3754181421,4.042037412
+11.79028746,-2.252052477,-2.654571002,-0.6593893397,3.543061087
+11.80032846,-1.507549751,-2.552090946,0.6664668095,3.03810014
+11.81036946,-2.01471414,-3.23897214,0.282970739,3.824929546
+11.82041046,-1.474178814,-3.421190968,0.7464105266,3.799326189
+11.83045146,-1.561765134,-2.923533859,-0.7106255668,3.389859769
+11.84049246,-1.75231069,-2.989977525,-0.4976588631,3.501174474
+11.85053346,-1.644475316,-2.905363929,-0.3321183407,3.354957707
+11.86057346,-1.505432182,-3.100424119,-0.4154815096,3.471538659
+11.87061446,-1.440917074,-2.923738804,-0.2848476952,3.271945723
+11.88065546,-1.765805625,-3.00374684,-1.411592703,3.759409335
+11.89069646,-1.595286199,-3.165049886,0.1646096456,3.548179134
+11.90073746,-1.299700969,-3.223713831,-0.7294220263,3.551564439
+11.91077846,-1.168555523,-2.975030872,-0.1936855102,3.202162516
+11.92081946,-1.551798117,-3.269112782,-0.7819025409,3.702235455
+11.93085946,-1.256089365,-3.388988597,-0.07689907193,3.615095804
+11.94090046,-1.203624199,-3.560320494,-0.4504823577,3.785172069
+11.95094146,-0.9937962806,-3.767342626,-0.4600817317,3.923286468
+11.96098246,-0.9171195491,-3.537935891,-0.1844878399,3.659526526
+11.97102346,-1.365134528,-2.909248234,-0.5497821128,3.260303351
+11.98106446,-1.219834727,-3.66274354,-0.3601282579,3.877290208
+11.99110446,-0.742666993,-3.444087787,-0.2127164429,3.529666165
+12.00114546,-1.588060794,-4.018936914,0.2624487662,4.329280582
+12.01118646,-0.8503176684,-3.185531512,-0.2638813341,3.307610091
+12.02122746,-1.297610589,-3.228592163,0.06916963756,3.480285194
+12.03126846,-1.018958969,-3.340212586,-0.4789711618,3.524870334
+12.04130946,-1.548721604,-3.709844323,-0.5371182132,4.055857429
+12.05135046,-0.9556616172,-3.594437243,0.1050955153,3.720794712
+12.06139046,-1.36694848,-3.7673704,0.359909572,4.023824398
+12.07143146,-0.6939027493,-2.910869959,-1.080261982,3.181451068
+12.08147246,-1.087969051,-3.53091397,-0.6964992785,3.759806027
+12.09151429,-1.271856382,-4.10331282,0.6209824884,4.340554574
+12.10155529,-0.9930223285,-3.637869484,-0.2998077965,3.782865639
+12.11159629,-1.375670187,-3.203322836,-0.6865695369,3.553184963
+12.12163729,-1.064660734,-3.817190432,-0.361035161,3.979295372
+12.13167729,-0.7271766955,-4.158517553,1.030907389,4.345667294
+12.14171829,-0.9781060083,-3.909843365,0.5549691778,4.068360516
+12.15175929,-1.345455431,-3.852195081,-0.5020132846,4.111164628
+12.16180029,-0.7673363958,-4.14519818,0.9630557138,4.324228186
+12.17184129,-0.4297874536,-4.171230277,0.619093253,4.238768186
+12.18188229,-1.202090913,-3.915085393,-0.544642995,4.131531459
+12.19192229,-1.185450907,-3.723441439,-0.6929909492,3.968569825
+12.20196329,-0.6905475439,-3.920877938,0.0294132489,3.981332045
+12.21200429,-0.5648191781,-3.815414048,0.0120195365,3.857013032
+12.22204529,-1.20748475,-3.743128429,-1.193073483,4.110043089
+12.23208629,-0.871213059,-3.590655849,0.3003942722,3.707028235
+12.24212729,-0.5863937227,-3.839485281,-0.5996237791,3.930019528
+12.25216829,-0.5508724724,-4.307013441,-0.2269742936,4.348027437
+12.26220829,-0.6379910886,-4.254832889,-1.023389039,4.422438317
+12.27224929,-0.9123698558,-4.034843094,-0.5754741937,4.17654739
+12.28229029,-0.7896007658,-3.856310644,-0.9807400328,4.056655292
+12.29233129,-0.4302401011,-3.831103297,-0.8358565539,3.944757939
+12.30237229,-0.5580258098,-3.793475587,-1.626013609,4.164825337
+12.31241329,-0.7847934774,-4.063990003,-1.165345986,4.299993815
+12.32245329,0.1654058354,-3.723950439,-1.209223493,3.918850267
+12.33249429,-0.9744945487,-4.212523606,-0.8671911979,4.40987702
+12.34253529,0.0498891383,-3.919169381,-0.2237817138,3.925870072
+12.35257629,-0.462734248,-4.305671798,-0.3086622351,4.341451945
+12.36261729,0.07022654006,-3.662664894,0.4114328974,3.686369884
+12.37265829,-0.5171737991,-3.756045806,0.3459879363,3.807237382
+12.38269829,-0.3140300887,-3.795807164,1.219484771,3.999238682
+12.39273929,-0.8339486074,-4.066116635,1.535739031,4.425750687
+12.40278029,-0.07955822116,-3.322744614,-0.9423717731,3.454710674
+12.41282129,0.1339951045,-3.316580187,0.39453269,3.342650874
+12.42286229,-1.299135397,-4.033676867,0.8071601737,4.31390883
+12.43290329,-0.2613798404,-3.686795769,1.059057639,3.844786801
+12.44294429,0.1174998168,-3.660696429,-0.1733389539,3.66668119
+12.45298429,-1.193143796,-3.93073342,0.3727184826,4.124703189
+12.46302529,-0.1049842354,-3.595576281,0.7766950107,3.680006199
+12.47306629,-0.3952112229,-3.915703152,0.105795427,3.937018638
+12.48310729,-1.650558759,-5.026144368,0.6671076643,5.332120034
+12.49314829,0.3003604497,-4.193650256,0.5169809872,4.236058098
+12.50318929,0.0714683973,-4.069811198,-1.271048443,4.264274272
+12.51322929,-1.750327022,-5.278339457,1.914834487,5.88142017
+12.52327029,0.1115013227,-4.537284103,0.4134075022,4.557442851
+12.53331129,0.8044267465,-3.818659253,-2.461343329,4.613834832
+12.54335229,-1.198369745,-5.131957921,1.415498058,5.456804642
+12.55339329,-0.2630233648,-4.889842555,-0.1733839774,4.89997995
+12.56343429,0.2179909238,-4.565649531,-0.238034302,4.577044462
+12.57347529,-0.3734683149,-4.993696999,-2.225371925,5.479851139
+12.58351529,-0.6534976121,-5.565210289,0.7623798573,5.655072743
+12.59355629,0.5795852979,-5.229214659,-2.185303879,5.69703064
+12.60359729,-0.6507524174,-6.967079072,-0.7589241529,7.038439839
+12.61363829,2.974362828,-12.15276764,2.954645432,12.85560287
+12.62367929,-0.9205468945,-5.78298165,-4.81285139,7.579829935
+12.63372029,-1.874713671,-5.935113337,-1.108254942,6.322052727
+12.64376029,-0.7128385187,-4.75027478,0.08885779738,4.80428402
+12.65380129,-0.8890847813,-4.852732909,0.1503085256,4.935795892
+12.66384229,-0.982344728,-4.727289083,-0.8752708805,4.906970792
+12.67388329,-1.135604563,-4.617302957,-0.3535951638,4.768030396
+12.68392429,-1.006881984,-5.086843729,0.136758188,5.187339709
+12.69396529,-0.5111192266,-5.161975772,0.8363091284,5.254203051
+12.70400529,-1.068816496,-4.665827245,-0.8830938703,4.867460053
+12.71404629,-1.657439908,-4.656852646,-0.2394247699,4.948808729
+12.72408729,-0.8083341484,-4.760914081,0.5705379742,4.862635146
+12.73412829,-0.9606578437,-5.555453625,0.3651802522,5.649715487
+12.74416929,-0.9771409985,-5.445862185,0.2114183611,5.536868898
+12.75421029,-1.336480248,-4.450350039,-0.3125523877,4.657197002
+12.76425029,-0.9730162995,-4.725489602,0.1999034393,4.828765276
+12.77429129,-1.163287986,-4.824040329,-0.2564354897,4.968939846
+12.78433229,-0.9029466292,-4.543628916,-0.1445320612,4.634734713
+12.79437329,-1.052413156,-4.770779504,-0.4893821293,4.909929265
+12.80441429,-1.429786022,-4.342104044,0.02760821342,4.57153342
+12.81445529,-1.198238767,-4.229321779,-1.734865376,4.725748272
+12.82449629,-1.609518175,-4.75327791,-0.9219316614,5.102367846
+12.83453629,-0.4927208164,-5.00081306,0.6062065744,5.061461398
+12.84457729,-0.7240711661,-4.570006876,-0.5972796303,4.665402968
+12.85461829,-1.953325246,-4.849523664,-1.367943823,5.40413079
+12.86465929,-0.9350319095,-5.092163526,-0.2802985615,5.184880069
+12.87470029,-1.083622962,-5.304349626,0.3822032511,5.427379018
+12.88474129,-1.644488033,-5.531229195,-0.5688837969,5.798488258
+12.89478129,-1.543857013,-5.688798793,0.2137765431,5.898442726
+12.90482229,-0.8451072876,-5.068054871,0.3633290237,5.15086347
+12.91486329,-1.301760066,-5.281572382,-0.9660103118,5.524740901
+12.92490429,-1.206230376,-5.905083207,0.9416397017,6.100138091
+12.93494529,-0.9428840623,-5.546629592,0.454912793,5.644561615
+12.94498629,-1.447296825,-4.656650917,-0.739530108,4.932136519
+12.95502629,-1.381986203,-5.084066302,-1.287073907,5.423483684
+12.96506729,-1.052018761,-6.008322816,0.3079120374,6.107495097
+12.97510829,-0.8420398383,-5.668662152,0.5506749827,5.757256692
+12.98514929,-1.677829003,-5.411933717,-0.7233695734,5.712039938
+12.99519029,-1.301485101,-4.56587231,-0.6523498768,4.792349505
+13.00523129,-0.3394070412,-4.704912666,-1.087933529,4.840970946
+13.01527129,-1.833569738,-5.857973945,-0.5942080879,6.166921434
+13.02531229,-1.542186318,-6.280495502,-0.5760969222,6.492676648
+13.03535329,-0.5605395644,-4.20627878,-0.9299148649,4.344160152
+13.04539429,-2.229339553,-4.724083055,-1.325547416,5.389247768
+13.05543529,-0.8319586538,-5.752566773,-0.4335201699,5.828560664
+13.06547629,-1.625965954,-5.671493374,-0.2901552129,5.907096784
+13.07551629,-1.861134682,-4.576653698,-1.062752495,5.053614968
+13.08555729,-1.129722995,-5.054797479,-1.03236393,5.28138494
+13.09559742,-1.483873644,-5.793101426,0.9943190217,6.062225288
+13.10563842,-1.229036344,-5.598754596,0.3667876518,5.743789388
+13.11567942,-1.714174711,-4.649849144,-0.4909287179,4.980010342
+13.12572042,-1.752141267,-4.584173802,-0.7638135946,4.966695045
+13.13576042,-1.535588904,-5.055175794,-0.009923894405,5.28326926
+13.14580142,-1.415511068,-5.437916989,-0.1795217997,5.621996161
+13.15584242,-1.971890741,-4.98223938,-0.6400847572,5.396366447
+13.16588342,-1.455606449,-4.648476217,-1.25339219,5.029722981
+13.17592442,-2.090175528,-4.641630297,-0.7353902793,5.143380641
+13.18596542,-1.544730587,-4.157830212,-1.214304723,4.598725978
+13.19600542,-1.515007875,-4.115043504,-1.480401567,4.628220036
+13.20604642,-1.477077133,-4.821830666,-1.062244372,5.153656075
+13.21608742,-1.490778036,-4.651249552,-0.4023597729,4.900860632
+13.22612842,-1.709451184,-4.568621963,-0.8379557043,4.949414081
+13.23616942,-1.932670249,-4.582192181,-0.09857645452,4.974074466
+13.24621042,-1.634303499,-4.39427875,-0.3551879454,4.701786058
+13.25625042,-1.39361997,-4.807940898,0.2803552794,5.013688401
+13.26629142,-1.732268773,-5.075429379,0.01154006481,5.362916339
+13.27633242,-1.473117398,-4.829422984,0.6430680066,5.089885822
+13.28637342,-1.372342098,-4.644153663,0.2383670086,4.848536368
+13.29641442,-2.090254173,-4.729272166,-0.1095791602,5.171768104
+13.30645542,-1.039235505,-4.306962571,-0.1406758225,4.432801226
+13.31649542,-1.428818893,-5.489295303,0.119006626,5.673451236
+13.32653642,-1.399822989,-4.555566007,0.3271090311,4.776995537
+13.33657742,-1.017958291,-3.967049014,-1.541932402,4.376216688
+13.34661842,-2.142524334,-4.406404705,-1.110198557,5.023878361
+13.35665942,-0.5839435932,-4.078624999,-0.5967288226,4.163202768
+13.36670042,-1.699025598,-4.784016723,-1.09312995,5.193114391
+13.37674042,-1.576721581,-3.902821736,-1.334461496,4.415750891
+13.38678142,-1.289506495,-4.113225313,-0.3209975213,4.322555827
+13.39682242,-2.054819023,-4.65120599,-1.314001504,5.251913778
+13.40686342,-1.408413718,-4.166586125,-0.383660962,4.414891264
+13.41690442,-1.57639136,-4.550931796,0.3183832312,4.826733659
+13.42694542,-1.693123126,-4.121994674,-0.9098858124,4.548120294
+13.43698542,-1.47386248,-4.345790129,-0.6115696406,4.62949024
+13.44702642,-1.51955043,-5.240631933,0.9481435597,5.538251779
+13.45706742,-2.165232581,-4.713677934,0.3457873768,5.1987076
+13.46710842,-1.98548274,-3.862066643,0.2277554816,4.348513887
+13.47714942,-1.375721643,-4.220487221,0.5832656085,4.477200151
+13.48718942,-1.384147773,-5.414503568,1.626435193,5.820481542
+13.49723042,-1.438348831,-4.882437349,0.6831331283,5.135534315
+13.50727142,-2.080146968,-4.110109624,0.2994593024,4.616241805
+13.51731242,-1.524191073,-4.13371074,0.1648254079,4.408842289
+13.52735342,-1.611491464,-4.550941152,1.672533472,5.109338345
+13.53739442,-2.450464438,-4.937729205,1.378906767,5.682194078
+13.54743442,-1.523162548,-3.483161806,0.7956990463,3.884015613
+13.55747542,-2.126909198,-4.408881001,0.4484808558,4.91559859
+13.56751642,-1.974662613,-5.385496116,2.910275005,6.432150609
+13.57755742,-1.721897713,-4.357589225,1.496981347,4.918787325
+13.58759842,-2.597057497,-4.043312494,-0.07976245344,4.806188262
+13.59763942,-1.387898762,-3.715846198,-0.04254024804,3.966810509
+13.60767942,-1.796283798,-4.455590606,0.8459476787,4.877965827
+13.61772042,-1.885518595,-4.317617367,-1.532758706,4.954427247
+13.62776142,-1.715225894,-4.005521062,-1.261520405,4.536257552
+13.63780242,-1.793591594,-3.947795595,-1.642246649,4.63670518
+13.64784342,-1.360540663,-3.878990531,-1.460650842,4.362469406
+13.65788442,-2.01492771,-4.084192133,-2.641248121,5.264670046
+13.66792442,-0.7001051833,-3.750157659,-1.409072553,4.066855689
+13.67796542,-1.382571364,-4.324471181,-1.879354752,4.913708259
+13.68800642,-1.785978519,-4.338166237,-1.692766593,4.987470732
+13.69804742,-0.8323379188,-4.037385171,-1.648223088,4.439583852
+13.70808842,-1.400390899,-4.28327433,-1.402293876,4.719529826
+13.71812942,-1.269516034,-4.225842394,-1.307062029,4.601937205
+13.72816942,-1.735233312,-4.037593332,-1.832743673,4.761527479
+13.73821042,-0.9682596626,-3.844512132,-0.7887309194,4.042263817
+13.74825142,-1.174881114,-4.125988322,-0.4871824068,4.317577095
+13.75829242,-1.733919004,-4.316977097,-0.9915456873,4.756672074
+13.76833342,-1.148242881,-3.711044172,-0.2324829555,3.891575373
+13.77837342,-1.515073071,-3.83813662,-0.8922166961,4.221704603
+13.78841442,-1.519328382,-3.877373191,-0.1913027698,4.168810184
+13.79845542,-1.173030105,-3.695697862,-0.321569379,3.890705486
+13.80849642,-1.803452192,-3.455213284,-0.3929907793,3.917318011
+13.81853742,-1.117113766,-3.40961465,-1.030751268,3.733076936
+13.82857842,-1.493429456,-3.786283219,-0.2227830094,4.076261084
+13.83861842,-1.630163086,-3.53938103,-0.5133638996,3.93041884
+13.84865942,-1.393129827,-2.891942815,-0.7289788073,3.291740278
+13.85870042,-1.420475062,-3.518915483,-0.8933873087,3.898545429
+13.86874142,-1.471226555,-3.997637261,-0.1313214469,4.261790301
+13.87878242,-1.599693684,-3.213937578,-0.1522696817,3.593271587
+13.88882242,-1.991392667,-3.247440955,-0.5272639006,3.845715113
+13.89886342,-1.574245432,-3.501629944,0.4235535908,3.86251972
+13.90890442,-1.932047521,-3.934714789,0.7564320695,4.448255565
+13.91894542,-1.669927368,-3.619064546,0.3177827221,3.998408616
+13.92898642,-1.337798502,-3.790925909,0.8806661063,4.115385385
+13.93902742,-1.649048277,-4.099813846,1.199839881,4.579022771
+13.94906742,-1.257527926,-3.71778952,0.7877936107,4.002993152
+13.95910842,-1.638272882,-3.56460358,-0.3415914148,3.937895556
+13.96914942,-1.347651938,-3.854322006,0.5497569698,4.119975315
+13.97919042,-0.9650800929,-4.330626252,0.4853931588,4.463329457
+13.98923142,-1.439146099,-3.563324501,0.1826190698,3.847307204
+13.99927242,-1.451736323,-2.810598982,-1.472033617,3.489109909
+14.00931242,-1.257956527,-3.56757338,-0.004730982184,3.782863575
+14.01935342,-1.06369492,-4.105927987,-0.3727360243,4.257819121
+14.02939442,-1.533140675,-3.664370527,-0.2275999457,3.978684886
+14.03943542,-1.319616293,-2.993325933,-0.9018470603,3.393333968
+14.04947642,-1.487125427,-3.040763808,-0.1429556519,3.387952611
+14.05951642,-1.065655564,-3.791452158,-0.2857814956,3.948721605
+14.06955742,-1.600447536,-3.827965389,0.4161112547,4.169880083
+14.07959842,-1.120678156,-3.080897635,-0.2143887466,3.285393782
+14.08963942,-2.110108248,-3.286114439,-0.5471742547,3.94341281
+14.09968079,-0.987650053,-3.297854771,0.5774394429,3.490663981
+14.10972179,-1.458368235,-3.733399832,-0.1260870194,4.010113483
+14.11976179,-1.627933835,-3.094659934,-0.1931516594,3.502056002
+14.12980279,-1.117875951,-3.080845302,-0.1038138056,3.279029083
+14.13984379,-1.969161114,-3.4529279,-0.0645965302,3.975484787
+14.14988479,-1.048138476,-3.134373053,-0.3633594292,3.324893799
+14.15992579,-1.593723092,-3.501328813,-0.6204001057,3.896684878
+14.16996579,-0.8252788677,-3.471537249,0.2492562783,3.576979839
+14.18000679,-0.6158594504,-3.733346914,-0.05447558463,3.784194714
+14.19004779,-1.326172776,-3.718927388,-0.09144811392,3.949369305
+14.20008879,-0.177845403,-3.291208826,-0.4005594152,3.320260888
+14.21012979,-1.324359116,-3.681282137,0.1734763634,3.916102563
+14.22017079,-0.6365306734,-3.704863373,0.005215716362,3.759150318
+14.23021079,-0.9698704243,-3.777933103,-0.1355098075,3.9027926
+14.24025179,-1.33990467,-3.161793279,-0.2716055059,3.444713459
+14.25029279,-0.7708515957,-3.269319482,-0.6758194309,3.426279901
+14.26033379,-1.606975514,-4.112909271,-0.1275757205,4.417541005
+14.27037479,-0.796470294,-3.145408211,0.2190805525,3.252069192
+14.28041479,-1.439283508,-3.174360407,-0.8886914098,3.596925553
+14.29045579,-1.601462174,-3.299432935,-0.5124751228,3.703183703
+14.30049679,-0.1511428867,-3.755124577,0.07036480844,3.758823748
+14.31053779,-1.512303683,-3.943359897,0.01823805034,4.223444369
+14.32057879,-0.9276068958,-3.089812885,-1.162573822,3.42913635
+14.33061979,-0.9194818973,-3.193171192,0.3465299731,3.340938827
+14.34065979,-0.701612961,-3.992873242,0.3698340511,4.070881317
+14.35070079,-0.760844013,-4.150232633,0.5605164313,4.25646487
+14.36074179,-0.6565736861,-3.610934578,0.3900063604,3.690805128
+14.37078279,-0.6754865782,-3.543421456,0.6230255055,3.660639085
+14.38082379,0.4773367189,-3.760761877,0.1257233226,3.793018138
+14.39086379,-1.14093335,-4.376856678,0.4819854015,4.548726549
+14.40090479,-0.4946882948,-2.658581315,0.1350490469,2.707583676
+14.41094579,-0.5116269476,-2.897143036,-0.9143068922,3.080772143
+14.42098679,-0.4262381571,-4.352176458,-0.04796120167,4.373261845
+14.43102779,0.1202245005,-3.751320378,1.261098236,3.959447849
+14.44106879,-0.9923145962,-2.823377779,-1.236424155,3.238038763
+14.45110879,-1.043993677,-2.022232929,-2.370051336,3.285801599
+14.46114979,0.3607008099,-3.556527405,-0.03447576821,3.574937879
+14.47119079,-0.9187415667,-4.163586212,0.469657132,4.289535409
+14.48123179,0.002300532752,-2.844285668,-1.243534954,3.104246356
+14.49127279,-0.7100299548,-2.522415158,-1.103180144,2.843189616
+14.50131279,-0.446680023,-2.97100331,-0.04447684586,3.004723265
+14.51135379,0.3069052565,-3.354315485,-0.1681425333,3.372520589
+14.52139479,-0.9040231747,-3.556483844,-0.7491142792,3.745264668
+14.53143579,-0.07840125818,-2.877664499,0.6246966398,2.94573346
+14.54147679,0.1125439452,-3.430896761,-0.5358926368,3.474320026
+14.55151679,-0.9613259612,-3.958585754,0.4936125898,4.103437847
+14.56155779,0.7268071514,-2.941278989,0.6516505498,3.099035199
+14.57159879,-0.2264040439,-3.334767074,-0.1022596157,3.344007664
+14.58163979,0.05043810049,-3.43104031,0.0152951467,3.431445112
+14.59168079,0.1845318402,-3.826883654,0.5340250361,3.868368291
+14.60172179,-0.3107914256,-3.301219259,-0.06363817155,3.316427253
+14.61176179,0.08959505819,-3.186729315,-0.01499459982,3.188023814
+14.62180279,-0.1977398781,-3.387987261,0.500683043,3.430487174
+14.63184379,0.1203671817,-2.860421352,0.2550555468,2.874291548
+14.64188479,-0.3654293436,-3.030068082,-0.5854431117,3.107667103
+14.65192579,-0.4137449596,-3.172513272,0.1963968641,3.205401235
+14.66196579,0.1586029289,-2.817702472,0.271588549,2.835200601
+14.67200679,-0.5620892227,-3.19519199,0.149620893,3.247704198
+14.68204779,0.1147291776,-2.579219688,0.3004363722,2.599191989
+14.69208879,0.2840097161,-2.79126604,0.342750333,2.826535939
+14.70212979,-0.0006283632643,-2.922109185,-0.1118999201,2.924251028
+14.71216979,0.700495485,-2.742859865,0.1973306644,2.837765592
+14.72221079,0.04786941409,-2.911894391,-0.5520449853,2.964148123
+14.73225179,0.2708990709,-2.062137252,0.2553192562,2.095467555
+14.74229279,0.8564613379,-2.640172234,0.7634604228,2.878698884
+14.75233379,0.3217121607,-2.534995734,0.07812757194,2.556522248
+14.76237479,0.6094871913,-2.151922856,0.8347292107,2.387261919
+14.77241479,0.6618362533,-2.064139046,-0.2121323061,2.178003063
+14.78245579,0.6499833624,-2.087812376,0.2124299294,2.196944552
+14.79249679,0.9842172258,-2.051329258,-0.4356836396,2.316561138
+14.80253779,0.1719764978,-1.986362453,-0.1663532853,2.000721152
+14.81257879,0.618742347,-1.559960099,-0.9876824319,1.947263256
+14.82261879,0.01474488717,-1.603043407,-0.6701821303,1.737558536
+14.83265979,0.8059105506,-1.347627818,-0.9322555053,1.826114147
+14.84270079,0.2678876087,-1.816875791,-0.478227396,1.897762592
+14.85274179,0.7612553646,-1.303920904,-0.9770691508,1.798439207
+14.86278279,0.3255704825,-1.45282449,-0.8571222925,1.717950454
+14.87282279,-0.08028820949,-1.263494717,-0.847318266,1.52342159
+14.88286379,0.9819166388,-1.494790542,-0.6658049047,1.908364541
+14.89290479,0.1018109149,-1.542458359,-0.3822009122,1.592363272
+14.90294579,0.8476867868,-1.766703757,-0.9146717584,2.162507683
+14.91298679,0.7078306708,-2.088693551,-0.9642041069,2.406938838
+14.92302679,0.5905752859,-1.776699426,0.05403645873,1.873061654
+14.93306779,1.262392078,-1.795251326,0.6054049212,2.276637038
+14.94310879,1.15499795,-0.3447550508,1.060286724,1.605329949
+14.95314979,1.351308202,-1.775741945,0.9485563731,2.424675752
+14.96319079,1.434476512,-2.376056719,0.7902640593,2.88580763
+14.97323079,1.571717388,-2.310569804,0.9270222473,2.94421443
+14.98327179,1.448586574,-2.015509069,0.3966020197,2.513557844
+14.99331279,1.044526066,-1.940782092,0.09491960585,2.206055203
+15.00335379,1.487562945,-2.209629758,0.2108722311,2.672035606
+15.01339479,0.9802569797,-2.299036902,0.1198112029,2.502164892
+15.02343579,1.718110325,-1.982721684,0.219465884,2.632727415
+15.03347579,1.345953614,-2.184294211,-0.01288492441,2.565715954
+15.04351679,1.316161466,-2.001272707,0.1570000792,2.400421312
+15.05355779,1.2722116,-1.86829489,0.1215039718,2.263583744
+15.06359879,1.339087521,-1.85344764,-0.1456927335,2.291211452
+15.07363979,1.349222208,-2.092085813,0.2548590803,2.502434168
+15.08367979,1.293150918,-2.207659831,-0.03914593935,2.558814888
+15.09372104,1.837857501,-1.877687273,-0.3546874237,2.651270046
+15.10376204,1.114827651,-1.979079015,-0.5650287277,2.340694748
+15.11380304,1.365780791,-2.053151105,0.1775577199,2.47230932
+15.12384404,1.578048607,-2.133901299,-0.4795973986,2.696995703
+15.13388404,1.404112798,-1.863026695,-0.6495128077,2.421625096
+15.14392504,1.769160465,-2.338642578,-0.8425019145,3.051063312
+15.15396604,1.398353876,-2.449690998,-0.09736783504,2.822385523
+15.16400704,1.582674193,-1.918252185,-0.8268091571,2.620717922
+15.17404804,0.812996645,-1.689205931,-1.231590262,2.2430325
+15.18408804,1.844540138,-2.089670913,-0.3222336227,2.805866596
+15.19412904,1.299480383,-2.21207331,-0.001598044038,2.565525316
+15.20417004,1.474527016,-1.734899143,-0.4386774141,2.318737336
+15.21421104,1.31681957,-1.943885063,-0.2704161823,2.363435599
+15.22425204,1.387867918,-2.014801995,0.535383929,2.504444127
+15.23429204,1.293294759,-2.032478274,0.5702742648,2.475639716
+15.24433304,1.381237175,-1.664113043,0.3785528344,2.195538796
+15.25437404,1.05490407,-1.750201892,0.3376971692,2.071248086
+15.26441504,1.222784136,-2.016724559,0.3892105544,2.390368977
+15.27445604,1.549899087,-2.202491624,0.246419794,2.704418468
+15.28449604,1.030387498,-2.123745124,0.7055238712,2.463687415
+15.29453704,1.577477626,-1.878887267,0.3226294792,2.47441767
+15.30457804,1.054561861,-1.958707024,0.1942018193,2.233013271
+15.31461904,1.71940373,-2.178564671,0.04211690962,2.775656147
+15.32466004,1.321305554,-2.491310017,0.4551156914,2.856502102
+15.33470004,1.745016727,-2.279135757,0.09122942805,2.871909815
+15.34474104,1.031446502,-2.001033264,-0.5133679926,2.309017693
+15.35478204,1.730287444,-2.050908259,-0.3877715546,2.711177992
+15.36482304,1.317283108,-2.457283607,-0.5146994036,2.835205987
+15.37486404,1.850381214,-2.24241612,-0.08058047891,2.908407452
+15.38490404,1.329973612,-2.061356941,-0.1753199905,2.459422564
+15.39494504,1.393318985,-1.931123076,-0.2043385524,2.390047776
+15.40498604,1.105821331,-2.415047122,-0.5231620789,2.707211107
+15.41502704,1.324851159,-2.366609811,0.2682766861,2.725443995
+15.42506804,1.370623894,-2.360677664,-0.4373389864,2.764538711
+15.43510804,1.295076552,-2.142066205,0.5501762152,2.562882122
+15.44514904,1.735768478,-2.475329284,-0.2157716131,3.030957714
+15.45519004,1.202444889,-2.49880527,0.5798432332,2.83304071
+15.46523104,1.799057132,-2.566765704,-0.6971401334,3.211058565
+15.47527204,1.018235376,-2.467020391,0.1858976036,2.67535994
+15.48531204,1.792840811,-2.358247561,-0.8988842762,3.09573944
+15.49535304,1.216111659,-2.562854209,-0.02915889502,2.836899629
+15.50539404,1.858486332,-2.563273746,-1.055391435,3.337393418
+15.51543504,1.078056997,-2.633563126,0.1914208835,2.852105114
+15.52547604,1.728574795,-2.645898997,-0.8017199242,3.260599202
+15.53551604,1.397840344,-2.706074155,0.1038126361,3.047551808
+15.54555704,1.698686606,-2.99516839,-0.5567134023,3.488050986
+15.55559804,1.089190388,-3.170384008,0.7086731815,3.426352016
+15.56563904,1.923766548,-2.976697913,-0.2031673551,3.550054249
+15.57568004,0.8708036077,-2.953690874,0.7314007241,3.165049086
+15.58572004,1.762144683,-2.925364915,-0.2268567646,3.422627318
+15.59576104,1.136940067,-3.104277434,0.7833099657,3.397461642
+15.60580204,1.730046539,-3.006333064,-0.1506979501,3.471859644
+15.61584304,1.082965735,-2.982655349,0.688058238,3.246917284
+15.62588404,1.654857339,-3.123120087,-0.1548056191,3.537851985
+15.63592404,1.112783245,-3.079544297,0.8325686646,3.378616612
+15.64596504,1.708750541,-2.819056394,0.07980338395,3.297465079
+15.65600604,1.190911987,-2.901967281,0.238466996,3.145878569
+15.66604704,1.540952847,-3.12819547,-0.1823068285,3.491901825
+15.67608804,1.261966255,-3.111386479,0.212571432,3.364293576
+15.68612804,1.453293583,-2.450768055,-0.59455015,2.910638448
+15.69616904,1.243525014,-2.425698995,-0.3130108094,2.743783126
+15.70621004,1.383713471,-2.782044981,-0.4661546499,3.141932113
+15.71625104,1.274396412,-3.002011094,-0.4992452127,3.299303352
+15.72629204,1.31570626,-2.612193014,-0.4179665762,2.954544189
+15.73633204,1.353801308,-2.569636102,-0.8100276482,3.015286465
+15.74637304,1.149617561,-2.478608695,0.3512305498,2.754720403
+15.75641404,1.683688205,-2.485001163,-0.09006583214,3.003023245
+15.76645504,0.7084482099,-2.840791664,0.2136174989,2.935579769
+15.77649604,1.326311355,-2.486299538,0.08798363864,2.819313449
+15.78653604,1.090205099,-2.293144955,0.8519592011,2.678226171
+15.79657704,0.9835785636,-2.029205295,-0.4205908066,2.293904433
+15.80661804,0.9195193195,-2.004044872,0.1821431065,2.212439319
+15.81665904,1.159803411,-2.605751722,0.2439277107,2.862618856
+15.82670004,1.138082466,-1.490873346,-0.01972675145,1.875719643
+15.83674004,0.5488257642,-1.804851431,-0.733962974,2.02420356
+15.84678104,1.269149998,-2.115626411,-0.1196925044,2.47000873
+15.85682204,1.136810112,-1.729043157,-0.5197040355,2.133546286
+15.86686304,0.9108210015,-2.159912784,-0.4275677043,2.382778268
+15.87690404,1.18776158,-2.031418758,0.3809998941,2.383820602
+15.88694404,1.101583123,-1.457228321,-0.09192056894,1.829056901
+15.89698504,0.6334483867,-2.042353929,-0.4007962275,2.175569821
+15.90702604,1.360214681,-2.03809467,-0.2647660178,2.464571952
+15.91706704,0.8877111972,-1.681225651,0.6358624828,2.004712437
+15.92710804,1.199842293,-1.816410207,-0.877840147,2.347247514
+15.93714804,0.9947720347,-1.713495264,0.01650785923,1.981390908
+15.94718904,1.059932017,-1.862666653,0.1868191248,2.151251804
+15.95723004,1.275461629,-1.364310655,-0.6537169558,1.978760165
+15.96727104,0.9029079645,-1.784109749,0.1686249286,2.006670066
+15.97731104,1.18123828,-1.916405927,0.3290596622,2.275129845
+15.98735204,0.4489940586,-1.579794732,0.2666067213,1.663858829
+15.99739304,1.057632746,-1.005748063,-0.5778160036,1.569709376
+16.00743404,0.630661019,-1.824512255,0.838481369,2.104668453
+16.01747504,1.558461458,-1.79910508,0.5583816129,2.444866301
+16.02751504,0.5785132475,-1.564480581,0.3212466127,1.698669024
+16.03755604,0.9177479786,-0.3774405112,-1.01356981,1.418466232
+16.04759704,0.8805180987,-1.132852278,0.04274080753,1.435441808
+16.05763804,1.001526884,-2.074792527,0.9749711698,2.50167722
+16.06767904,0.5349378596,-1.005485742,-0.2158218992,1.159197646
+16.07771904,0.8171595702,-0.3309420637,-0.9045742017,1.263141678
+16.08776004,0.9954411755,-0.973573466,-0.109896664,1.396719623
+16.09780046,0.8226404578,-1.173590195,1.136839056,1.829331656
+16.10784146,1.07278047,-0.6424074174,-0.6498624712,1.409207741
+16.11788246,0.5982103609,-0.3446586083,-0.440462569,0.8189337377
+16.12792246,0.7087438598,-0.5671101537,0.2046847075,0.9304985839
+16.13796346,0.5735054362,-0.2446327387,-0.04784718096,0.6253343225
+16.14800446,0.5408484079,-0.2563836504,-0.3967809445,0.7181118954
+16.15804546,0.8263932008,-0.4832031207,0.4315929276,1.050087346
+16.16808546,0.6426773395,-0.429149632,-0.08258724332,0.7771899524
+16.17812646,0.3958944335,-0.3211271833,0.04061008215,0.5113748616
+16.18816746,0.877140016,-0.1123298458,-0.3286643904,0.9434049414
+16.19820846,0.4243220245,0.03892834984,0.06936785817,0.4317134428
+16.20824946,0.8782813925,-0.1066956241,-0.3862682354,0.9653835043
+16.21828946,0.8332110543,-0.5743795584,-0.1882136858,1.029357532
+16.22833046,0.5692569224,-0.4830354153,-0.3092890567,0.8081066617
+16.23837146,0.8403965514,-0.1044900543,0.08472030759,0.8510946279
+16.24841246,0.7662566344,0.1246230594,-0.4267333066,0.8858789148
+16.25845346,0.6725303721,-0.2945821033,0.03973358452,0.7352921017
+16.26849346,0.9276125968,-0.4004011019,0.3693873239,1.075747725
+16.27853446,0.7085563103,-0.1855065345,-0.09505058348,0.7385792663
+16.28857546,0.5490569485,-0.1821225316,-0.263241064,0.6355533077
+16.29861646,0.6710093652,-0.1988462444,0.868921389,1.115714021
+16.30865746,0.8840832192,-0.2935111127,0.3001732475,0.978701124
+16.31869746,0.396479484,-0.03783553264,0.09861621559,0.4103080144
+16.32873846,0.8424883197,0.2464296977,-0.1346660542,0.8880591821
+16.33877946,0.5152889857,0.1049904755,0.6248036438,0.8166549651
+16.34882046,0.5568467553,-0.1811912528,0.265960604,0.6431513211
+16.35886046,0.7963465523,-0.1197480621,0.2518407476,0.8437601507
+16.36890146,0.5894240788,-0.2042909341,0.2627300173,0.6768918617
+16.37894246,0.8309144872,-0.004640368614,0.2031439662,0.8553992572
+16.38898346,1.136349644,-0.1157309975,0.2399539429,1.167159831
+16.39902446,0.2836591207,0.2045683297,-0.05989244521,0.3548208045
+16.40906446,0.7587131415,0.5082578185,-0.5657099283,1.074243624
+16.41910546,0.773713223,0.5657220978,-0.153466022,0.9706829881
+16.42914646,0.6074757126,0.1212545698,-0.06200504422,0.6225544455
+16.43918746,0.9267803919,0.369116342,0.1497939706,1.008765088
+16.44922746,0.5969120963,0.4136572879,-0.3973329216,0.827822356
+16.45926846,0.9593229244,0.4678618906,-0.2220562005,1.090185387
+16.46930946,0.5536213946,0.3182653367,0.3653363729,0.7357038388
+16.47935046,0.5656574861,0.4941953745,-0.2392592937,0.7883162242
+16.48939146,0.7939196654,0.6461242001,-0.1527514923,1.034948277
+16.49943146,0.7914394227,0.3601640355,-0.6392351568,1.079220125
+16.50947246,0.8213892268,0.02772278231,-0.001686336994,0.8218586607
+16.51951346,0.8516158964,0.2149498235,0.8711637962,1.23708505
+16.52955446,0.6553973725,0.7701983155,-0.2769334888,1.048543427
+16.53959546,0.5813217383,0.5930717546,-0.5616192162,1.002539383
+16.54963546,0.9032947578,0.01091998586,0.2537522024,0.9383234228
+16.55967646,0.8736289092,0.4713140868,-0.2530786031,1.024408717
+16.56971746,0.3261799085,0.7088519602,-0.347340982,0.8541136879
+16.57975846,0.9284389546,0.5260982582,0.6315010446,1.239988645
+16.58979946,0.6896828869,0.03969952449,0.1418628073,0.7052400959
+16.59983946,0.6289480772,0.688472294,-0.8229002935,1.243677883
+16.60988046,0.6702463035,0.8319694711,-0.6456822968,1.248322449
+16.61992146,0.3337570595,0.4180353906,0.6277371919,0.8247431992
+16.62996246,0.7635139979,0.3503385571,0.1217653424,0.848833039
+16.64000246,0.8297292566,0.3868511298,-0.7297488856,1.170742445
+16.65004346,0.7646797865,0.5603265065,0.1644488472,0.9621561168
+16.66008446,0.8181371516,0.2896380632,-0.1191025203,0.8760274064
+16.67012546,0.9015989922,0.4458837419,-0.409546001,1.086011501
+16.68016646,0.2709813522,0.7847806866,-0.167855435,0.8470460828
+16.69020646,0.8583750585,0.678368817,0.2172258157,1.115427742
+16.70024746,0.796116172,0.5008631738,-0.455068329,1.0448694
+16.71028846,0.6910436071,0.2065530756,-0.2268345451,0.7560815768
+16.72032946,1.163176743,0.05366888814,-0.110478462,1.169643525
+16.73036946,0.9537177835,0.5023280475,0.3452523565,1.131861417
+16.74041046,0.1342539169,0.4231786015,-1.154582432,1.236998317
+16.75045146,1.066791678,0.4564347136,0.7455065471,1.379187132
+16.76049246,0.7690501416,0.03103709377,-0.5513503361,0.9467780176
+16.77053346,0.5937387392,-0.1213292132,-0.5006959069,0.7860934166
+16.78057346,1.170458938,0.1707323017,0.3472181904,1.232754686
+16.79061446,1.313919205,0.3331770888,-0.08978808939,1.358474346
+16.80065546,0.1182341905,0.04471150193,-1.065444553,1.072916836
+16.81069646,0.966208167,0.2118768193,0.991336357,1.400427714
+16.82073646,0.5038694466,0.1605984191,-0.4033842051,0.6651278737
+16.83077746,0.5956412405,0.1739362469,-0.1542419475,0.6394004095
+16.84081846,1.036537381,0.2063046786,0.9231057823,1.403244685
+16.85085946,0.6150376973,0.01874968171,0.4653705382,0.7714873023
+16.86090046,0.5042303295,0.1979939214,-0.166605885,0.5667515673
+16.87094046,0.5672374768,0.4144174625,0.7610648185,1.035721896
+16.88098146,0.8107442245,0.4023750488,-0.1783927023,0.9225160344
+16.89102246,0.4630341005,0.3527404105,-0.7614758778,0.9584737283
+16.90106346,0.9678546698,0.161946714,-0.4267602038,1.070090497
+16.91110346,0.9977751647,-0.2183243613,-0.3292988133,1.073153537
+16.92114446,0.9922726424,-0.2190887751,0.1790475905,1.031825047
+16.93118546,0.8283982842,0.6139417098,-0.488725487,1.141061235
+16.94122646,0.6627029568,0.7171615114,-1.083757448,1.45877553
+16.95126746,0.8603603344,0.1501340958,-0.2773422092,0.916339922
+16.96130746,0.8245996405,-0.1424867783,0.3682944793,0.9142799749
+16.97134846,1.011261256,0.2709294947,-0.5508042061,1.182978188
+16.98138946,0.4022309515,0.417655614,0.1884890896,0.6097163989
+16.99143046,0.6639369386,0.5359697469,0.5848168749,1.034449905
+17.00147046,0.4272053597,-0.1894856013,-0.02354907632,0.4679356488
+17.01151146,0.6162451474,-0.1475344603,0.4927518797,0.8027010113
+17.02155246,1.233136558,0.2862061131,0.5661999249,1.386766767
+17.03159346,0.294565457,-0.3319690906,-0.6455045414,0.7833571334
+17.04163446,1.123369337,-0.3485433522,0.4997732162,1.277972771
+17.05167446,0.6661094715,0.06722021241,0.2410029334,0.7115495759
+17.06171546,0.4348301289,0.1704206816,-0.6202363837,0.7764107298
+17.07175646,1.111462652,-0.7432138538,0.4121211147,1.399128254
+17.08179746,0.7386905209,-0.7846511708,1.115563962,1.551071919
+17.09183746,1.173852589,-0.01504159681,-0.1236376208,1.180441617
+17.10187804,0.7094074456,0.1093130754,-1.231724748,1.425606582
+17.11191904,1.096323406,-0.07097350359,0.1611533564,1.110375006
+17.12196004,0.4284634612,-0.03407384522,-1.02677867,1.113111136
+17.13200104,0.6595956733,-0.05641729876,-0.2396738613,0.7040546311
+17.14204104,0.9038552865,-0.04899875354,0.5412779224,1.054673905
+17.15208204,0.1021660145,0.1990690782,-0.09540667892,0.2432464322
+17.16212304,0.962243097,0.3696997114,-0.1152322483,1.03724063
+17.17216404,0.7278922485,-0.0254129494,0.4357649159,0.8487426025
+17.18220404,0.5403546836,-0.2931528611,0.7832251811,0.99567237
+17.19224504,0.991098156,-0.08487343155,0.2154529399,1.017791248
+17.20228604,0.1719953368,0.04869159199,-0.3654492241,0.406824781
+17.21232704,0.8059598134,0.2011731256,0.2301119095,0.8619706133
+17.22236804,1.437889532,-0.2413767897,-0.1051072097,1.461792251
+17.23240804,0.4835556713,-0.9286815409,-0.08078045368,1.050143311
+17.24244904,0.7736154284,0.4860598145,0.5680879909,1.075852657
+17.25249004,0.884879683,0.5304834872,-1.40668455,1.744473046
+17.26253104,0.3280109276,-0.5541705213,0.627776953,0.8993331073
+17.27257104,1.006093121,-0.5101995692,0.927466051,1.460383595
+17.28261204,0.3855535961,0.2004722272,-0.9672733104,1.060404803
+17.29265304,1.035820877,0.3342921162,-0.1313927829,1.096330321
+17.30269404,0.650414156,-0.6613870409,0.8218290836,1.239304012
+17.31273404,0.6658055625,-0.7223051608,-0.3549411929,1.044511868
+17.32277504,1.208120927,0.02617619377,-0.393247472,1.270781233
+17.33281604,0.7045074058,0.008567413464,-0.3954185432,0.8079355852
+17.34285704,0.7821348947,-0.3219517503,-0.3607387072,0.9195217985
+17.35289804,1.280829665,-0.6329313467,-0.7151302618,1.597666427
+17.36293804,0.602278013,-0.4290038536,-0.1916454166,0.7638789675
+17.37297904,1.171624507,-0.2231738227,0.0625710547,1.19433064
+17.38302004,0.6666831565,-0.4816688113,-0.6953924006,1.077052397
+17.39306104,0.7236985523,-0.1236612289,-0.4758668751,0.8749176972
+17.40310104,1.247586051,-0.3014142459,-0.8355565917,1.5314948
+17.41314204,0.8461681187,-1.29448993,0.3809636414,1.592745416
+17.42318304,0.8453176412,-0.6218898301,0.1903566903,1.066557333
+17.43322404,0.2491623026,0.539094499,0.1212589735,0.6061422857
+17.44326504,0.6242518859,-0.2071439368,-0.6846697766,0.9494059883
+17.45330504,0.8308761149,-1.630451938,1.787572762,2.558152658
+17.46334604,0.9042985055,-0.5334078259,0.6924132442,1.257662831
+17.47338704,0.5234261172,0.8499673471,-0.1458307278,1.008804239
+17.48342804,0.3173298553,0.1166146763,-0.293032043,0.4473980308
+17.49346804,0.6957383365,-1.044206223,0.7956054908,1.485734353
+17.50350904,0.5993289332,-0.3365660619,-0.3308717144,0.7628551472
+17.51355004,0.6801424237,0.3691737908,-0.8877476692,1.177700696
+17.52359104,0.9157039382,-0.4352817532,-0.5036715549,1.132108185
+17.53363104,1.201497713,-0.9827945982,0.2487604344,1.572057165
+17.54367204,1.147345772,-0.1191513811,-0.563803736,1.283929135
+17.55371304,0.5154199633,0.1699102928,-1.891595314,1.967907538
+17.56375404,0.9249778415,-0.3054942868,-0.3675062746,1.041139582
+17.57379504,0.8795377399,-0.8440229946,0.3856893611,1.278560806
+17.58383504,0.4554815079,-0.2495194395,-0.2151863068,0.5621641231
+17.59387604,0.6945437504,0.1923185773,-0.8181535238,1.090299337
+17.60391704,0.5442054771,-0.4773262304,0.5007046777,0.8801733385
+17.61395804,0.8320736977,-0.9096750203,1.028928691,1.605786266
+17.62399804,0.115382339,-0.1529144834,0.2811984479,0.34024769
+17.63403904,0.3464291087,0.5027091763,0.2000613141,0.6424594716
+17.64408004,0.527356579,-0.567857172,0.7999955803,1.113804138
+17.65412104,0.654092347,-0.8260976972,0.7081919557,1.269570813
+17.66416104,0.6905856239,-0.168116367,-0.515998655,0.878308732
+17.67420204,0.3033934918,0.2493716512,0.1025315112,0.4058898152
+17.68424304,0.6182668222,-0.01340042956,0.4382856506,0.7579760857
+17.69428404,0.06671011593,-0.4834254611,-0.2968689859,0.5712106536
+17.70432504,0.956966935,0.2248830735,-0.5250156462,1.114450331
+17.71436504,0.7397500364,-0.02954243582,-0.02832742095,0.7408814444
+17.72440604,0.02159686917,-0.2870850592,0.6632596117,0.7230474179
+17.73444704,1.03129177,0.1170366991,-0.05571051657,1.039405583
+17.74448804,0.435036426,-0.1700069911,-0.7426677239,0.8773336977
+17.75452804,0.2412798173,-0.2497062581,0.4686005402,0.5832286274
+17.76456904,0.463433575,-0.09949267667,0.7723394197,0.9061885292
+17.77461004,0.7129445726,-0.4524364607,-0.104499684,0.8508283602
+17.78465104,0.7077693482,-1.063345695,0.3353144288,1.320635182
+17.79469104,0.7883023185,-0.4663966149,0.5380292094,1.062271989
+17.80473204,0.7025580172,0.1777279836,-1.023912365,1.254420796
+17.81477304,0.645477498,-0.2882167878,-0.8171717763,1.080499805
+17.82481404,1.112834628,-0.5074398661,0.6375073045,1.379243158
+17.83485504,0.06202035205,-0.2578024225,0.1477556312,0.3035462727
+17.84489504,0.5085229897,0.1874422187,0.02188145041,0.5424103745
+17.85493604,0.7261044623,-0.5943672053,0.05843707323,0.9401675151
+17.86497704,0.3164836901,-0.758927515,0.1175851679,0.8306378096
+17.87501804,0.791634939,0.09452444371,0.3930457431,0.8888789025
+17.88505804,-0.1492927454,0.2790771146,-0.3926346838,0.5043157292
+17.89509904,0.8991911819,-0.04115032833,0.2935384119,0.9467855778
+17.90514004,0.2985754044,-0.4419582502,0.575683524,0.7847839747
+17.91518104,0.09815765684,0.1264487428,-0.2000390947,0.2562027509
+17.92522104,0.7602342215,0.2411423529,-0.005149058104,0.7975789734
+17.93526204,0.5090244616,-0.2162004698,-0.0500580132,0.5552966327
+17.94530304,0.7184773542,-0.1456795407,-0.07133661568,0.7365603504
+17.95534404,0.0262020951,-0.3129643971,0.1699592632,0.3570986066
+17.96538504,0.9784952867,-0.06352122724,0.8025619233,1.267120205
+17.97542504,0.3823583851,-0.1794859124,0.2318198812,0.4818231882
+17.98546604,0.4526309902,-0.3098403395,0.06988065898,0.552954931
+17.99550704,1.003817166,-0.7485862756,0.5374064809,1.362657712
+18.00554804,0.5734001863,-0.8416824272,0.2213293916,1.042211006
+18.01558804,0.6313505519,-0.1942978964,-0.1331925559,0.6738660467
+18.02562904,0.7880228215,-0.202319253,-0.7130083072,1.081801226
+18.03567004,0.3107253886,-0.9476775366,-0.4963666284,1.114012033
+18.04571104,1.047972049,-0.1835366441,-0.03871441483,1.064626658
+18.05575104,0.4851969482,0.3640527628,-1.047110023,1.210119785
+18.06579204,0.2155425119,-0.3181425817,-0.9710593826,1.044332132
+18.07583304,0.9283497845,-0.1341781041,0.3273236239,0.9934675842
+18.08587404,0.01708331204,0.3044147811,-0.9134467667,0.9629876397
+18.09591404,0.02720712641,0.4874151991,-0.8914542192,1.016368255
+18.10595517,1.047511289,-0.1892097224,0.6637823528,1.254466911
+18.11599617,0.2015008255,-0.262284898,0.1569129556,0.3660841789
+18.12603717,0.5908737497,0.548144527,-0.2849880284,0.8548756558
+18.13607717,0.01354890316,0.07184693143,-0.313425377,0.3218400554
+18.14611817,0.4430990785,0.2356943194,0.5409966713,0.7379471553
+18.15615917,0.2167326213,0.1561006312,-0.576464712,0.6353361318
+18.16620017,0.1703678191,0.07685159985,0.1926464599,0.2684101725
+18.17624117,0.9694747871,-0.08427171651,0.5428157401,1.114285427
+18.18628117,-0.1512950605,-0.06520595625,0.6345217162,0.6555606916
+18.19632217,0.6603881172,0.09441765893,0.3763232911,0.7659284425
+18.20636317,0.3219081155,0.1603521052,-0.485594303,0.6042677052
+18.21640417,0.240649122,0.3288625745,-1.134297271,1.205277102
+18.22644417,0.7119715228,-0.2644866305,-0.6034075123,0.9700295114
+18.23648517,0.7824224315,-0.2908482907,-0.02899517298,0.8352354815
+18.24652617,0.5776076234,0.5635904953,-0.9441890877,1.242078036
+18.25656717,0.0004224796034,0.7407347806,-0.876334489,1.147453847
+18.26660717,0.5689994987,-0.3825488216,1.606779778,1.746953143
+18.27664817,0.202970779,-0.5164442493,0.9417683405,1.093087099
+18.28668917,-0.6916840234,0.4585995356,0.3511907887,0.9011522026
+18.29673017,0.6805615959,0.9208944384,0.5484214658,1.269636466
+18.30677017,-0.1157699181,-0.0599659374,0.1233481836,0.1794808123
+18.31681117,0.3055991712,0.1797052561,0.5566087371,0.6599228127
+18.32685217,0.2420124917,0.6856120554,0.786948688,1.0714113
+18.33689317,-0.1234412731,0.9059053203,-0.5963774049,1.091589761
+18.34693417,0.1363663697,0.423102405,-0.4885717052,0.6605404931
+18.35697417,0.3800919312,0.07638886582,0.2509630805,0.4618307079
+18.36701517,0.2164744667,0.4299056039,-0.470423702,0.6730367615
+18.37705617,-0.03703068853,1.009718541,-0.3531145227,1.070323629
+18.38709717,0.3802020781,0.8303652875,-0.194851445,0.9338239751
+18.39713717,0.376649785,0.467412459,-0.3023975283,0.6721485941
+18.40717817,-0.08957935293,0.3282491285,0.6485550338,0.7323903213
+18.41721917,0.5050956078,0.3147244821,0.4377494609,0.7387812012
+18.42726017,-0.1003957883,0.4312597094,-0.8378527933,0.9476610969
+18.43730017,0.4503016788,0.9361975519,-0.4258772743,1.122768414
+18.44734117,0.3215227109,0.1800822918,0.1897526729,0.4145027893
+18.45738217,0.2931558212,-0.2612948913,0.4826777118,0.6222484466
+18.46742317,0.670992993,0.680531629,0.3770688111,1.027392711
+18.47746317,-0.2408575387,0.4727394552,-1.391893433,1.489584599
+18.48750417,0.63302154,-0.06077873692,0.2373653805,0.6787876316
+18.49754517,0.356115058,0.1648740128,-0.2455123061,0.4629013578
+18.50758617,-0.2953520537,0.4592885934,-0.5096409774,0.7469355886
+18.51762617,0.9130034747,0.3882432056,0.08757257938,0.9959804658
+18.52766717,0.1347620674,-0.3646211487,0.1804088223,0.4285519106
+18.53770817,0.08892812843,0.4022205726,0.06436848879,0.4169327325
+18.54774917,0.1315900077,0.754750995,-0.9038941705,1.184900699
+18.55778917,-0.003067663463,0.08257160202,0.03352676511,0.08917131824
+18.56783017,0.646964445,-0.01208751038,0.7056127489,0.9573914833
+18.57787117,-0.1465883442,0.3002789724,-0.8815326637,0.9427382676
+18.58791217,-0.2497671057,0.6921596213,-0.1576292396,0.7525393847
+18.59795217,0.5757511324,0.5742380923,0.5690217912,0.9924840311
+18.60799317,-0.08150023679,0.1313267459,0.324992339,0.3598736212
+18.61803417,0.8506134644,0.4026252,0.5771014738,1.103945845
+18.62807517,0.2592451316,0.3128157682,-0.07156933486,0.4125335293
+18.63811617,0.01780803331,0.1859608997,0.4464746761,0.4839816306
+18.64815617,0.2855458893,0.4572404234,0.03134809256,0.5399888542
+18.65819717,-0.524211983,0.5095995718,-0.6030075628,0.9476856269
+18.66823817,0.633596102,-0.2869308024,0.8482976747,1.096987808
+18.67827917,0.7599868843,-0.9066452855,1.335163747,1.783885638
+18.68831917,0.8052403135,-0.149560155,-0.09611243784,0.8246319198
+18.69836017,-0.003316428799,0.2636043222,-0.5428473151,0.6034744774
+18.70840117,0.4766214582,0.5015506236,-0.9836472684,1.202615064
+18.71844217,-0.06900806255,0.1686458689,-0.2324420249,0.2953520556
+18.72848217,0.2260969372,-0.02151300274,0.1655305821,0.2810391572
+18.73852317,0.4001384522,0.008313425034,1.089330429,1.160526035
+18.74856417,-0.2010058222,0.589780759,0.1194714797,0.6344431563
+18.75860517,-0.07124868818,0.8739325259,-0.3131979203,0.9310893473
+18.76864517,0.4958564954,0.2411223262,0.5653403842,0.7896982907
+18.77868617,0.1896044094,0.07176083118,-0.1165057719,0.2338226761
+18.78872717,-0.009491776032,0.6087828577,0.4382774645,0.7501958394
+18.79876817,-0.0003348718677,0.4769719988,0.4658353919,0.6667120909
+18.80880817,-0.1198069819,0.07878596842,0.6454700428,0.6612053523
+18.81884917,0.247947781,0.7598064977,0.5210693604,0.9540950133
+18.82889017,0.06534327902,0.664484311,-0.008172068596,0.6677394151
+18.83893117,0.05134024364,-0.003481541835,0.7705694675,0.7722857283
+18.84897117,0.3569504423,0.1422671788,0.7982829309,0.8859510179
+18.85901217,-0.3121565312,0.3081523945,-0.7703010803,0.8864329374
+18.86905317,0.299942319,0.7838978302,-0.1141674703,0.8470510104
+18.87909417,0.5375754654,0.2878758586,-0.4998796356,0.7885046234
+18.88913417,0.06400981236,-0.3939884239,0.03604749978,0.4007786877
+18.89917517,0.8674285948,0.3969014702,0.314036411,1.004281839
+18.90921617,-0.2003647481,0.6111061392,-1.530862454,1.660462766
+18.91925717,0.6881577138,0.255725126,-0.8431953943,1.118004853
+18.92929717,0.4997849107,-0.174933051,0.5848490345,0.7889454496
+18.93933817,-0.1966424288,0.6031693479,-0.7357153845,0.9714724052
+18.94937917,0.4926989258,1.114484858,-0.4213065058,1.289312958
+18.95942017,0.3730689136,-0.02237634413,-0.05221212745,0.3773688134
+18.96946017,-0.4240254245,0.190586559,0.1976967001,0.5051779709
+18.97950117,0.4254973514,0.7299630399,-0.5473262823,1.006707552
+18.98954217,0.1075496648,0.4911627892,-0.02274449944,0.5033141446
+18.99958317,0.09401301334,0.3081306867,0.3861910522,0.5029179809
+19.00962317,-0.2837145231,0.5562985058,0.004448561668,0.6244851863
+19.01966417,-0.1359498653,0.3029379937,0.2588310939,0.4210075167
+19.02970517,0.08536121724,0.1806036077,1.105461143,1.123364829
+19.03974617,-0.3766953932,0.7191958308,0.1914805251,0.8341503785
+19.04978717,-0.03424511839,0.8371687422,-0.08841399372,0.8425207804
+19.05982717,0.7548370953,0.2178059691,0.09189133286,0.7909883044
+19.06986817,-0.09067663777,0.03034036148,-0.07689439416,0.1227010107
+19.07990917,0.5926223596,0.3387612893,-0.3106812787,0.749988886
+19.08995017,-0.006207627975,0.3938490409,-0.3035587853,0.4972962274
+19.09999029,0.2253979208,0.1517919642,-0.09005647659,0.2862781725
+19.11003129,0.2550111445,-0.3931152153,0.7853939134,0.9145566442
+19.12007229,0.2644846571,0.02477647997,0.4057008719,0.4849321657
+19.13011329,0.4329048235,0.5032071398,-0.630964855,0.915827855
+19.14015329,0.2435482994,0.6357129402,-0.5420234424,0.8701931559
+19.15019429,0.3931973687,-0.1329355708,0.5138708532,0.6605598311
+19.16023529,0.1752143569,-0.1936292673,-0.09488510728,0.2778408674
+19.17027629,-0.1080023306,0.6342102789,0.1937428129,0.6718805391
+19.18031629,-0.1845020194,0.5114335144,-0.2442323506,0.5960324454
+19.19035729,-0.1054861275,0.3212790282,0.6048932898,0.6929959806
+19.20039829,0.4878344079,0.1817829911,0.1832125622,0.5519006326
+19.21043929,0.2470197183,0.3539018503,0.03430912256,0.4329461592
+19.22047929,0.2264892853,0.4655439813,0.3961307341,0.6518804747
+19.23052029,-0.3634085459,0.1859606805,-0.2071738672,0.4577861478
+19.24056129,0.3178946232,0.6793349232,-0.2037666947,0.7772218442
+19.25060229,0.06699079599,0.5787821829,-0.733782295,0.9369701374
+19.26064229,0.2636125814,-0.04156511519,0.5308108217,0.5941206782
+19.27068329,0.1290009611,0.07728849649,0.577468679,0.5967284431
+19.28072429,-0.1242850355,0.5742290657,-0.4636649054,0.748445679
+19.29076529,0.2152395165,0.7218001807,-0.4463647485,0.8755370003
+19.30080529,-0.08410966641,-0.02891356777,-0.08668497205,0.1241962752
+19.31084629,0.2442859074,-0.2061057637,0.992252031,1.042458289
+19.32088729,0.4747061297,0.2254526288,-0.3403021038,0.6260833165
+19.33092829,-0.148864647,0.4635440142,-1.026334866,1.135956423
+19.34096829,0.04591885147,0.7549246573,0.005523279905,0.7563400596
+19.35100929,0.6494077771,0.4563983878,-0.9951288611,1.27291453
+19.36105029,0.02541007604,0.08199948851,0.5351079404,0.5419502708
+19.37109129,0.4000227505,-0.0998133599,0.625813458,0.7494153667
+19.38113129,-0.457290746,0.5829421113,-1.079432262,1.309240368
+19.39117229,0.03487917584,0.5885168833,-1.254845223,1.386436156
+19.40121329,0.4036526654,-0.2022594652,0.4353795844,0.6272158704
+19.41125429,-0.5027677947,-0.2462494207,0.8887949055,1.050414498
+19.42129429,0.8644307274,0.7859175315,-1.638342463,2.012230821
+19.43133529,0.263102156,0.7554897176,0.9699209297,1.257272472
+19.44137629,0.4203777852,-0.1741484278,-0.6336709464,0.7801179561
+19.45141729,-0.2275582112,0.2309472939,1.122977062,1.168844247
+19.46145729,-0.64156593,0.674779796,-0.9576277435,1.335659205
+19.47149829,0.4868738565,0.09885134675,0.8659825784,0.9983704558
+19.48153929,-0.04205597067,-0.7146102981,0.9528417975,1.19178189
+19.49158029,0.4630503631,0.2330515241,0.113506735,0.5306716786
+19.50162029,0.3563178467,0.3000390539,-0.7405311513,0.8748555468
+19.51166129,0.2313309626,-0.3410108959,0.5687013638,0.7022988585
+19.52170229,0.5176679619,-0.5921788117,0.3212238085,0.8496120285
+19.53174329,-0.06655767719,-0.23296356,-0.2073370045,0.3188896018
+19.54178329,0.06074337954,0.4482276348,-0.06273594618,0.4566547599
+19.55182429,0.3849134721,-0.09481881447,0.4122573549,0.5719310406
+19.56186529,0.05195732589,-0.6873169573,0.1759719551,0.7113861767
+19.57190529,0.3342171988,-0.3532455369,0.5142333806,0.7077566778
+19.58194629,-0.1081410193,0.6299135256,0.3548108,0.7310104196
+19.59198729,-0.2512676108,0.4563139686,-0.0736363256,0.5260990008
+19.60202829,0.2122058348,0.04667280424,0.6151153922,0.6523623324
+19.61206829,-0.3070771281,-0.09910295974,-0.6463330919,0.722401706
+19.62210929,0.8655751006,1.104280224,0.1975844336,1.41693143
+19.63215029,0.5609778132,0.2184854155,-1.56998208,1.68145048
+19.64219129,-0.8194334793,-1.078776205,1.397076405,1.946034894
+19.65223129,0.8211223014,0.6543147605,-0.6519569439,1.235887332
+19.66227229,0.2871572906,0.4710140881,-2.293015439,2.35843876
+19.67231329,0.3819603359,0.4281352862,0.6130443084,0.8396528125
+19.68235429,0.8396530779,-1.94253728,1.485840647,2.585766966
+19.69239429,0.3895235266,-0.4417368966,-0.6859403765,0.904087531
+19.70243529,-0.1894532407,0.7761290002,-1.734507526,1.909655758
+19.71247629,0.791670607,-0.7860958716,-0.2806815541,1.150422185
+19.72251729,0.3737713469,-1.463383246,1.052517529,1.84092061
+19.73255729,0.9768122388,0.3633760207,-1.018781433,1.457436067
+19.74259829,-0.7723861244,0.02518059567,-1.573317917,1.752867267
+19.75263929,0.6549167313,-0.8092176627,1.388984444,1.735807286
+19.76268029,0.60222981,-1.201654272,1.132488728,1.757607593
+19.77272029,-0.6898234393,-0.5326283555,-1.647334312,1.863668339
+19.78276129,1.007279229,0.2902772735,0.4207802564,1.129569991
+19.79280229,0.3613611433,-0.7748568653,0.04301036417,0.8560577837
+19.80284329,0.009083539881,-0.269629549,-1.505355729,1.529339229
+19.81288329,0.8572488116,-0.6872004515,0.5565134275,1.23159538
+19.82292429,-0.03785816319,-0.6468960325,0.2426612037,0.691948103
+19.83296529,-0.2497995212,-0.4812319878,0.6563382626,0.8513306888
+19.84300629,0.2849193602,-0.5475571376,-0.5979976684,0.8594178682
+19.85304629,0.8726982518,-1.311662179,1.472282124,2.156310405
+19.86308729,0.8063297229,-0.5098373342,-0.06680970132,0.9563290571
+19.87312829,-0.1133028407,-0.1252477613,-0.6674351084,0.6884723374
+19.88316929,0.3770211197,-0.5751766801,0.5747421223,0.8962709663
+19.89320929,0.3383058278,-1.053693477,0.5069530123,1.217260092
+19.90325029,-0.1668567306,-0.3725495712,-0.1479684699,0.4341992856
+19.91329129,0.7488179715,-0.8289261416,0.1863653809,1.132510025
+19.92333229,1.017844344,-1.489521031,1.107155081,2.116712636
+19.93337229,0.05601210499,-0.6052919603,-1.372728599,1.501299277
+19.94341329,0.006611803053,0.01557760376,-0.6122520107,0.6124858384
+19.95345429,0.2287928142,-0.7434086392,1.300184534,1.515084941
+19.96349529,-0.06997670864,-1.166266338,1.807412365,2.15216481
+19.97353529,-0.7317563809,-0.7097345974,0.5725710511,1.169199815
+19.98357629,0.7472258478,-0.172126351,-0.04216427207,0.7679529765
+19.99361729,-0.05382798722,-1.295842976,0.76467372,1.505600335
+20.00365829,-0.1667322762,-1.044599741,1.166218391,1.574501066
+20.01369829,0.3571756332,-0.5030475474,1.207101538,1.355627305
+20.02373929,-0.4256513525,-0.2278916486,0.2629124504,0.5497605242
+20.03378029,-0.1784666148,-0.7359562167,1.929161335,2.072473243
+20.04382129,0.104672725,-0.9513068303,-0.2282454783,0.9838887453
+20.05386129,0.4845972066,0.1549056431,-0.8558247954,0.995623569
+20.06390229,0.7469793876,-0.3433947327,-0.04506332159,0.8233643488
+20.07394329,0.4954133861,-1.19616666,-0.4284833783,1.363762115
+20.08398329,-0.06447457921,-0.2067694957,-0.4492731535,0.4987554132
+20.09402429,-0.05411618186,1.147301625,-1.34204475,1.766440968
+20.10406621,0.4367632549,-0.2801261782,-2.389258854,2.444952083
+20.11410721,-0.1035153052,-2.349587981,0.7174007356,2.458849917
+20.12414721,1.538199686,-0.682733398,-0.3944701248,1.728522446
+20.13418821,0.02750080738,-0.5850239759,-0.7535616714,0.9543922356
+20.14422921,-0.04903482355,0.2315516036,0.05833240807,0.2437688021
+20.15427021,0.3548259296,-0.06665204577,-0.1271582294,0.3827703631
+20.16431021,-1.085797176,-0.4010222589,-0.5808840376,1.295067807
+20.17435121,1.233402168,-0.4521375583,0.4347375602,1.383729029
+20.18439221,-0.3246326622,-1.064581577,-0.4826110536,1.213109116
+20.19443321,-0.6253389564,0.1536447641,-0.9064891648,1.111925416
+20.20447321,0.7331301843,0.2759009437,0.02063950181,0.7835988686
+20.21451421,0.2867043872,-1.133143616,-0.7092619962,1.36721119
+20.22455521,-0.02324735999,0.09811258759,0.9910919434,0.9962076891
+20.23459621,0.260655681,0.3562506403,-1.867679617,1.919136018
+20.24463621,-0.263914718,0.01529525634,-1.413505327,1.438013294
+20.25467721,0.5200888554,-1.12304372,0.9649350089,1.569337181
+20.26471821,0.2475708915,-0.1825874949,-0.3175599432,0.4421242553
+20.27475921,0.03142469108,0.4909533127,-0.7701718569,0.9138858548
+20.28479921,0.2526053441,-0.1624492821,0.5119500428,0.5935419745
+20.29484021,-0.4070187247,-0.2573952736,0.8810765809,1.004097859
+20.30488121,-0.04080557101,-0.02272918705,-0.8908595574,0.8920832145
+20.31492121,0.0813456693,-0.4658928408,2.222640105,2.272400118
+20.32496221,-0.1482372042,-1.107898555,1.42545996,1.811449578
+20.33500321,0.3614248779,0.2018363461,1.090164242,1.166114886
+20.34504421,-0.9171191105,-0.0504691821,0.7736649835,1.200921358
+20.35508421,0.1770037694,-0.9615686207,2.443307008,2.631671271
+20.36512521,-0.9992515866,-0.2822760532,3.253063345,3.414762749
+20.37516621,-1.222488705,-0.282123112,0.3823096704,1.311576444
+20.38520721,0.2464310133,-0.6541272841,3.94197937,4.003475003
+20.39524721,-0.962230964,-1.030733288,2.024678527,2.467310818
+20.40528821,-0.5046394153,-0.1387068457,1.456589951,1.547757996
+20.41532921,0.4227230669,0.08341604959,1.909430491,1.957441654
+20.42537021,-0.4908578935,-0.3798512086,0.2099325836,0.6552099678
+20.43541021,0.1580117388,-0.5814074731,1.535230324,1.649222394
+20.44545121,0.1314952371,-0.5315105141,0.09012781262,0.5549030966
+20.45549221,0.413193421,0.2259777088,-0.3105239886,0.564109808
+20.46553321,-0.1294682267,0.4604798174,-1.031476908,1.136990895
+20.47557321,0.8463316946,-0.05225817427,-0.6898977721,1.093145548
+20.48561421,0.04398410831,-0.440462167,-1.403957409,1.47208625
+20.49565521,-0.1973032556,0.2441135425,-1.340242054,1.376505997
+20.50569621,1.01225002,0.1363253844,-1.182077209,1.562223173
+20.51573621,-0.05155374924,-0.7027138455,-1.014642774,1.235299355
+20.52577721,0.1661849403,-0.3746488678,-0.6066819531,0.732149029
+20.53581821,0.7056454202,0.5547984026,-2.392847875,2.555671669
+20.54585821,0.08863679091,0.06981992103,-4.020884036,4.022466872
+20.55589921,-0.1315746313,0.6478839196,0.2069078189,0.6927310463
+20.56594021,0.4288093606,-0.04507026516,-1.351063496,1.418196519
+20.57598121,-1.027564243,0.06193805706,-1.098180774,1.505232743
+20.58602121,-0.1790991008,0.7209078956,-1.050078655,1.286254199
+20.59606221,-0.2897625906,0.5254508983,-1.120113096,1.270714111
+20.60610321,0.3709727964,0.4543023072,-0.8204485559,1.008537176
+20.61614421,0.5444876418,-0.1134014485,0.8786026239,1.039840974
+20.62618421,-0.2309140744,0.2893215096,-0.94019427,1.010442235
+20.63622521,-0.4861482536,0.4903528402,-1.83807224,1.963490665
+20.64626621,0.08138291789,0.674051306,0.09394019723,0.6854145484
+20.65630721,-0.05790696831,0.03253631987,-0.04091706097,0.07801304358
+20.66634721,0.1219627772,0.8450990284,-0.9830929524,1.302128657
+20.67638821,0.246452849,0.05285247065,-0.8370914859,0.8742165327
+20.68642921,0.272595403,-0.7107137136,1.119368745,1.353664886
+20.69647021,0.7175352947,0.1206210788,0.6817362285,0.9970810544
+20.70651021,-0.59529567,0.07537905168,-0.9203681159,1.098697595
+20.71655121,0.6512541085,-0.299031871,0.7628312624,1.046643926
+20.72659221,0.1639329766,-0.9761605666,0.5543973202,1.13451305
+20.73663221,-0.570496459,0.5194766885,-0.3268616939,0.8379503604
+20.74667321,0.7408429541,0.5744203062,-0.1733021164,0.953331314
+20.75671421,-0.2157981631,-1.485190875,0.9745308745,1.789433209
+20.76675521,-0.3954206628,-0.7278708331,1.636504683,1.834203105
+20.77679521,-0.2382379496,0.8812746553,-1.328185095,1.611669317
+20.78683621,-0.06128095793,0.609954128,-1.612537531,1.725130918
+20.79687721,0.1070923394,-0.1141175497,2.823446776,2.827780628
+20.80691821,-0.2764282529,-0.7270005481,1.22177688,1.448337364
+20.81695821,-0.2801030269,0.5794236955,-0.3479262882,0.7316025059
+20.82699921,-0.07336015429,0.3691869836,1.057240325,1.122246784
+20.83704021,-0.5114484979,0.01035432257,1.407396156,1.497481458
+20.84708121,-0.5650770403,0.08999332666,-0.9088567024,1.07397922
+20.85712121,0.6133330147,-0.3555147316,1.082254128,1.293770501
+20.86716221,-0.3467701475,-0.05948737934,1.406013874,1.449366516
+20.87720321,-0.9097491337,0.4634063854,-0.9680983526,1.40698379
+20.88724321,0.4333552053,0.411498971,-1.089438602,1.242579818
+20.89728421,0.9419310392,-1.45294275,0.1129600203,1.735233899
+20.90732521,0.1188420452,-0.5183197803,-0.7132936513,0.88970032
+20.91736621,-0.1301889143,0.4277660346,-1.334518799,1.407435028
+20.92740621,-0.4232553462,0.5417498658,-1.59234768,1.734418963
+20.93744721,-0.3835840711,0.909371696,1.582305672,1.864881997
+20.94748821,-0.6348339576,-0.6357022691,-1.167898881,1.473471861
+20.95752921,0.04051299096,-0.6949105901,-1.322138489,1.494186138
+20.96756921,0.7493250713,0.3210005545,-0.1147217864,0.8232195981
+20.97761021,-0.2300336847,0.8625552329,-1.596942422,1.829519644
+20.98765121,-0.7943464391,0.07353794619,-1.334182,1.554488888
+20.99769221,0.2974033849,-0.003844873197,2.034853266,2.056475473
+21.00773221,-0.8788103463,0.1564872783,-0.1725484103,0.9091583178
+21.01777321,-0.1046530729,0.2574764768,-0.7507719648,0.8005653907
+21.02781421,0.2730612068,-0.5246791755,1.548001812,1.657154269
+21.03785521,-0.08808194496,0.4350725325,-0.3943906027,0.5937933017
+21.04789521,-0.3056737415,0.4988493927,-0.367440201,0.690868623
+21.05793621,-0.1478890208,-0.7839563754,1.304881602,1.529436091
+21.06797721,-0.524907692,-0.510361464,1.292864989,1.485764715
+21.07801721,-0.0354585938,0.3129655666,-1.160681663,1.202658172
+21.08805821,0.8575038233,-0.1599259528,-1.687107072,1.89926812
+21.09809879,-0.1183571831,-1.456623426,0.609823662,1.583554586
+21.10813979,0.2271494542,-0.5241520125,0.7620869118,0.9524225259
+21.11817979,-0.4765915278,0.4127689131,-0.8260080886,1.039137634
+21.12822079,-1.016844762,0.303669919,-1.698440731,2.002720551
+21.13826179,-0.8138168632,-0.1235350387,2.549430463,2.679021179
+21.14830279,-0.6755228309,-1.071908284,-1.667639353,2.094358965
+21.15834279,-0.248749818,-0.8605938575,1.896466044,2.097398798
+21.16838379,0.1142277332,-0.2512189693,0.5378192943,0.6044903133
+21.17842479,-0.7529991692,0.1440746628,-2.585337045,2.696615081
+21.18846479,-0.8591876022,-0.3488062942,0.8707498133,1.272035536
+21.19850579,-1.517356263,0.115462519,1.400130406,2.06786527
+21.20854679,-0.5475676992,0.8353016531,-0.1791405612,1.014716994
+21.21858779,-0.1199569996,-1.369928514,0.7937308735,1.587798008
+21.22862779,-1.268946661,-1.468283359,2.838089958,3.438144305
+21.23866879,0.2243058985,0.7242591541,0.2774866354,0.8073805121
+21.24870979,-1.050453681,0.5104463217,-1.468658019,1.876423396
+21.25875079,0.1005614746,0.06556234404,2.672117327,2.674812524
+21.26879079,-1.61677267,-1.360550603,0.2033755159,2.12283146
+21.27883179,-0.4954285888,-0.03885094732,-0.3158981645,0.5888552735
+21.28887279,0.3955254376,-0.2810707594,-0.001432567835,0.485224892
+21.29891279,-0.585218542,-0.5309034635,-0.5609690058,0.9690332579
+21.30895379,0.06339185759,0.6381192888,-0.6545472604,0.9163224707
+21.31899479,-0.8646295327,-0.1701703477,-1.481374544,1.723662587
+21.32903579,-1.314400138,-0.8944517212,0.2745753068,1.613407327
+21.33907579,-2.041920796,-1.193054407,-0.2451041704,2.377581841
+21.34911679,-0.6984895246,-0.5261020954,-2.141861406,2.313491153
+21.35915779,-1.241219603,-0.6858787615,-1.70522467,2.217847369
+21.36919879,-0.7322273011,-0.3699005267,0.7375514102,1.103161503
+21.37923879,-1.08141783,0.1251739036,0.3291029316,1.137295815
+21.38927979,-2.268399977,-0.007927581891,-1.691766719,2.829801394
+21.39932079,-1.251898373,-0.4200353211,-0.6237862283,1.460406952
+21.40936179,-2.094547345,-1.725614642,0.9743712455,2.883448248
+21.41940179,-3.251056581,-2.017993843,1.756228763,4.210226539
+21.42944279,-2.084761299,-0.1940748616,-1.465366622,2.555620093
+21.43948379,-0.9627101433,0.5623809622,-0.2079521316,1.134163681
+21.44952379,-2.235169812,-1.9185042,2.777204071,4.048395349
+21.45956479,-2.619124304,-0.234434683,-0.4703389174,2.671327467
+21.46960579,-1.428740686,0.591028774,-1.647356531,2.259291593
+21.47964679,-2.990145632,-2.154709785,3.765389948,5.268956882
+21.48968679,-3.187499685,-2.27698939,0.4951802284,3.948422265
+21.49972779,-3.171634727,-0.1413703986,0.6641372788,3.243505936
+21.50976879,-1.342956185,0.5352838685,-0.8996947002,1.702794964
+21.51980979,-2.256107229,-1.45047581,3.564377877,4.460794722
+21.52984979,-2.929182562,-1.730487565,0.566563037,3.449013101
+21.53989079,-2.250327256,-0.2358867293,-0.2839951712,2.280409737
+21.54993179,-3.409508816,-0.8417207265,1.253074687,3.72873173
+21.55997179,-2.668024861,-1.391455185,2.212232646,3.734766053
+21.57001279,-1.927654508,-0.8844713281,-0.9897985393,2.340479135
+21.58005379,-2.618369136,-0.185317304,-1.051972568,2.827869466
+21.59009479,-1.625672424,-0.06300235994,-1.365618385,2.124074787
+21.60013479,-3.856492784,-1.881329796,0.8886639279,4.381970102
+21.61017579,-1.686876985,-0.3371414644,0.2287986249,1.73538674
+21.62021679,-2.076944448,-0.2795805234,-3.451308514,4.03774615
+21.63025779,-2.61305811,-0.246895465,0.0707162261,2.625648651
+21.64029779,-1.828341012,-1.278203096,1.469170235,2.671159896
+21.65033879,-3.989439172,-1.402751713,-0.6733419657,4.282140432
+21.66037979,-2.70244625,-0.04090997122,0.4646647793,2.742408196
+21.67041979,-1.892408807,-0.3961819703,1.458803122,2.422040007
+21.68046079,-3.947719581,-2.477361776,0.5473613656,4.692698129
+21.69050179,-2.970069217,-1.068847048,-0.05895221293,3.157090516
+21.70054279,-2.573282133,-0.1222353489,-4.141453038,4.877330795
+21.71058279,-2.853568123,0.3968812608,2.262230433,3.66306597
+21.72062379,-3.83873479,-1.353510702,-0.9023177612,4.169178978
+21.73066479,-3.34875186,-1.419480889,0.9217726171,3.752163345
+21.74070579,-3.929678582,-1.513735374,-0.6356753719,4.258855682
+21.75074579,-3.870227309,-1.256002534,-1.315179718,4.276201525
+21.76078679,-4.677501504,-1.499415397,-1.783979064,5.225882523
+21.77082779,-4.006437905,-0.9961287349,2.511450459,4.832307994
+21.78086779,-3.774470382,-1.389690056,-2.282654173,4.624756771
+21.79090879,-3.888498981,-1.282831313,-1.070745054,4.232325067
+21.80094979,-2.719375401,-0.5742115971,1.581971211,3.198023521
+21.81099079,-3.605457198,-0.9744557378,-1.715414028,4.109930764
+21.82103079,-3.56559936,-0.5279599386,0.2328834897,3.611990478
+21.83107179,-2.893650786,-0.8788395093,-0.2023341268,3.030926072
+21.84111279,-3.851948913,-1.01142527,-2.504580565,4.704616383
+21.85115379,-3.442112598,-0.2116893064,-0.535703187,3.489975559
+21.86119379,-2.541629985,1.331286166,-1.396109276,3.190819166
+21.87123479,-5.793479156,3.677856838,-0.01773986757,6.862313484
+21.88127579,-6.052441227,0.8612268917,4.166888427,7.398426571
+21.89131579,-6.638839774,1.171096138,0.2726293534,6.746850115
+21.90135679,-4.628654449,1.498246831,-0.799395656,4.9303366
+21.91139779,-3.635677655,1.316196257,-0.2564401674,3.87508531
+21.92143879,-5.115640097,-0.3728873575,-0.3290204859,5.139754183
+21.93147879,-4.285074103,0.2102883501,0.8477538836,4.373187386
+21.94151979,-5.428685405,0.1352887096,1.389120684,5.605228321
+21.95156079,-4.463235256,0.5548216087,1.033681308,4.614844853
+21.96160079,-4.719015565,0.8597370943,0.01128103316,4.796705436
+21.97164179,-4.850696324,-0.1593189387,-1.433842528,5.060685896
+21.98168279,-5.039316391,0.2378373239,-0.4185349256,5.062257181
+21.99172379,-5.571176203,0.5271342752,-0.2951990211,5.603839513
+22.00176379,-5.098823504,0.5579233374,-0.2745671207,5.136600693
+22.01180479,-4.926864493,-0.01666865766,0.05428028762,4.927191688
+22.02184579,-4.654112056,0.7615345692,-0.7688614959,4.778267671
+22.03188679,-4.944397954,0.5395388874,-1.22336206,5.121990636
+22.04192679,-3.945682996,0.1280189395,0.595039562,3.992352093
+22.05196779,-4.805974479,0.1676258222,0.4412057501,4.829094286
+22.06200879,-4.402171906,-0.5596184452,0.3146515381,4.448740932
+22.07204879,-3.794680113,-0.8343429291,1.865239574,4.309854285
+22.08208979,-4.228605788,-0.08966387261,1.315310696,4.429355342
+22.09213079,-3.665561605,0.1129714041,0.2478710729,3.675669257
+22.10217167,-3.986866105,-0.9552135012,1.796168754,4.47590844
+22.11221167,-5.08973927,-0.9572007506,1.108247341,5.296214807
+22.12225267,-4.403084656,-0.09543750471,-0.2966666722,4.414099446
+22.13229367,-4.438674611,-0.621308763,-0.5277667612,4.512914207
+22.14233367,-4.187052842,-0.7396262947,0.09837414086,4.253014934
+22.15237467,-4.451020423,-0.07053443251,-0.7349973464,4.511848735
+22.16241567,-4.78491924,-0.2174097289,-1.410509214,4.993220941
+22.17245667,-4.742181357,-0.9405567243,0.007108460069,4.834561149
+22.18249667,-5.153999001,-0.5040745012,-0.09945119798,5.17954509
+22.19253767,-4.731116086,-0.2085096819,-0.6902819341,4.785752276
+22.20257867,-4.766677682,-0.7898215713,0.1550623119,4.834157482
+22.21261967,-4.562067526,-0.7200895777,0.4098956645,4.636701799
+22.22265967,-4.195042185,-0.1880173838,-0.07461047173,4.199916213
+22.23270067,-3.964147626,-0.8274089353,-0.5948998135,4.093040158
+22.24274167,-3.896192163,-1.618219417,0.5525437528,4.25490917
+22.25278167,-3.175768417,-1.410499127,0.003774377704,3.474913966
+22.26282267,-3.327584354,-0.9495729116,-0.9575581616,3.59046292
+22.27286367,-2.779708141,-1.292366368,0.2443475407,3.0751738
+22.28290467,-2.947035573,-1.266713025,0.1891416389,3.21330906
+22.29294467,-3.852964282,-0.2928004019,-0.5845759696,3.908042336
+22.30298567,-3.546144505,-0.8175582772,-0.7106226432,3.707900609
+22.31302667,-3.456613693,-2.4027668,1.5328125,4.480064807
+22.32306667,-2.967660749,-1.919059685,1.301370349,3.766080878
+22.33310767,-3.255883457,-0.9254300505,-0.01920810342,3.384902778
+22.34314867,-2.775261042,-0.9380701958,-0.9357614958,3.075337236
+22.35318967,-3.256186928,-1.687953165,-0.5417813677,3.707487862
+22.36322967,-4.433343413,-1.77308497,0.06043799043,4.775145744
+22.37327067,-3.357028009,-1.629984161,0.3571789223,3.748874791
+22.38331167,-2.950860821,-0.8572645991,0.5099397701,3.114886956
+22.39335267,-3.287498767,-0.651186427,-0.9555326861,3.484929644
+22.40339267,-2.651690664,-1.722094326,1.12722214,3.356739787
+22.41343367,-3.065817081,-2.006290787,1.326357256,3.896621699
+22.42347467,-2.593161497,-1.524174701,-0.1463353425,3.011479553
+22.43351467,-2.426702377,-1.50549694,-0.06602675915,2.856530237
+22.44355567,-2.529967421,-1.703956994,0.6373248714,3.11614948
+22.45359667,-2.163360448,-1.470612597,0.4370811242,2.652144368
+22.46363767,-1.740904965,-1.819956104,0.5174142659,2.571129682
+22.47367767,-1.583246635,-2.225160255,0.5925533259,2.794481618
+22.48371867,-2.061859217,-1.630589055,0.02011968434,2.628780877
+22.49375967,-2.359346984,-1.360405008,-1.603656195,3.160527356
+22.50379967,-1.395030611,-1.855382922,-0.7680089718,2.445075454
+22.51384067,-2.292784474,-2.014650552,-0.7347324675,3.139348545
+22.52388167,-1.733753235,-1.900582192,-0.8051691967,2.695628013
+22.53392267,-1.969079984,-1.691949883,-0.7517303234,2.702789091
+22.54396267,-2.413222791,-1.865257554,-0.374519425,3.07296189
+22.55400367,-2.102780078,-1.891509213,0.3018993455,2.844404046
+22.56404467,-2.602313266,-2.286629695,-0.07345447719,3.464982721
+22.57408467,-2.39197167,-2.759423858,0.6319542038,3.706118537
+22.58412567,-2.233186582,-2.626684461,0.6048266315,3.500344101
+22.59416667,-2.065204555,-1.746515368,-0.01109801531,2.704719755
+22.60420767,-2.573596129,-1.510306567,-0.5904284477,3.041879141
+22.61424767,-2.476543751,-1.507763759,1.099382962,3.100848819
+22.62428867,-2.318307863,-1.833527931,0.785638327,3.058366165
+22.63432967,-2.178775902,-2.141866668,-0.732887671,3.141939145
+22.64437067,-1.414273067,-2.111237345,0.3821167123,2.56972851
+22.65441067,-1.726918425,-2.49023676,0.9650402588,3.180381906
+22.66445167,-1.370739815,-2.974400834,-0.1291340035,3.277600274
+22.67449267,-0.7946485209,-3.409374622,-0.5379245442,3.541844774
+22.68453267,-1.270985439,-4.126637948,-0.46528283,4.342929064
+22.69457367,-1.848968965,-3.626688146,0.9189232689,4.173244915
+22.70461467,-2.104770909,-3.143592066,-0.4396001047,3.808606032
+22.71465567,-1.978338173,-3.030488204,-0.7600093961,3.698012299
+22.72469567,-2.032417463,-2.893647863,0.1440397257,3.539020505
+22.73473667,-1.985165674,-2.953653159,-0.7147998941,3.62986069
+22.74477767,-1.919278518,-3.18933805,-0.1804953611,3.726672215
+22.75481767,-1.939420275,-2.789417443,-1.77143971,3.831474823
+22.76485867,-2.425769454,-2.945381396,-0.6994082683,3.879278404
+22.77489967,-1.938851487,-3.335680994,1.571280747,4.165913581
+22.78494067,-0.5222503883,-2.698253211,-1.230650615,3.011281587
+22.79498067,-2.6921303,-3.592557948,-0.9941611469,4.598085966
+22.80502167,-2.263352952,-4.22023199,0.5530273175,4.820680849
+22.81506267,-2.716531023,-3.339717911,-0.3654603338,4.320511287
+22.82510267,-1.752597642,-2.479243995,-0.6413553572,3.10315742
+22.83514367,-1.060697345,-3.039183306,0.1417867935,3.222082792
+22.84518467,-0.9779506186,-3.448901215,-0.662797097,3.645628478
+22.85522567,-1.102058209,-3.448633705,-0.7639749777,3.700170874
+22.86526567,-1.842465546,-3.744057259,-1.17199661,4.334307338
+22.87530667,-1.704082124,-4.248843878,1.583805483,4.84406957
+22.88534767,-1.972201374,-3.890017503,-0.5120950538,4.391361495
+22.89538767,-2.222990646,-3.795901304,0.06199276507,4.399363275
+22.90542867,-2.040816696,-3.532483362,0.8585215312,4.168984374
+22.91546967,-1.845054839,-3.160001692,0.3720741194,3.678080641
+22.92551067,-1.97382997,-2.811860226,-0.3980369264,3.458467301
+22.93555067,-2.276613853,-2.954300154,-0.144572407,3.732527456
+22.94559167,-1.57853071,-3.34781075,-0.3931591791,3.722119042
+22.95563267,-1.874989221,-3.210256464,-0.3478958827,3.733947333
+22.96567267,-2.093738529,-3.165779326,-0.5734206516,3.838581901
+22.97571367,-1.938444375,-3.317990828,-0.3069180107,3.854974499
+22.98575467,-1.51501533,-3.262417136,0.1889095044,3.60198887
+22.99579567,-1.471535142,-3.123242878,-0.1860092854,3.457551331
+23.00583567,-1.772522906,-3.899559282,0.0002642941475,4.283503253
+23.01587667,-1.991506103,-4.112770692,0.9156833267,4.660413638
+23.02591767,-1.497216405,-4.013902753,-0.6086893022,4.32707464
+23.03595767,-1.828149662,-3.607554887,-0.4049190992,4.064547075
+23.04599867,-1.128945461,-3.673766126,-0.6856743282,3.904001112
+23.05603967,-2.101845693,-3.810096298,0.1992345178,4.355948061
+23.06608067,-1.427432372,-3.503518302,-1.424045518,4.042290107
+23.07612067,-1.718951301,-2.94106235,-1.427412345,3.693527761
+23.08616167,-1.644599861,-3.596027101,-0.3437408513,3.96916583
+23.09620267,-1.497163049,-4.378681594,0.08581373692,4.62835972
+23.10624317,-1.178653884,-3.835443393,-0.811023429,4.09360599
+23.11628417,-1.525118734,-3.766558515,-0.2117282635,4.069125097
+23.12632517,-1.453461252,-3.928733672,-0.4089384753,4.208886854
+23.13636617,-1.606027972,-4.224244934,1.078768603,4.646214891
+23.14640617,-1.812157234,-3.84879434,-0.08797077477,4.254981853
+23.15644717,-0.2734763226,-3.615580483,1.477008428,3.915196728
+23.16648817,-2.310274081,-3.934848105,-0.5276281822,4.593341642
+23.17652917,-1.185989143,-4.230158224,1.158615841,4.543478789
+23.18656917,-0.4979334995,-4.000879542,0.04190173209,4.03196362
+23.19661017,-2.696887594,-4.462032776,1.131322793,5.335056743
+23.20665117,-0.7079305851,-3.742755961,-0.3136580962,3.822011159
+23.21669117,-1.755880123,-4.255535139,0.5791836673,4.639843537
+23.22673217,-1.715100617,-3.876449331,-0.6730624688,4.29202081
+23.23677317,-0.9033474559,-3.932969395,-0.0122013849,4.035397596
+23.24681317,-0.5949782393,-3.449210533,-1.696314683,3.889541864
+23.25685417,-2.047960239,-4.029125687,-1.625607228,4.803185797
+23.26689517,-1.303052447,-4.355158246,-0.6005002767,4.585406155
+23.27693617,-1.25051653,-4.234717005,-0.7317287529,4.475717448
+23.28697617,-1.259130209,-4.154003502,-1.722906066,4.670070587
+23.29701717,-0.7537049282,-5.218290891,0.951391688,5.357590605
+23.30705817,-1.691649336,-4.818120023,-0.297473588,5.115119605
+23.31709817,-1.210617761,-4.276472849,-1.070845626,4.571709281
+23.32713917,-1.567973416,-4.657113724,-0.03483303308,4.914108486
+23.33718017,-1.466803282,-4.814864586,0.5572981238,5.064090644
+23.34722117,-1.542850561,-4.173058116,-0.2025440419,4.453742918
+23.35726117,-1.872538507,-3.941685547,-0.7346430051,4.425266744
+23.36730217,-1.294762995,-4.610062057,-0.07271305025,4.788984294
+23.37734317,-1.452487252,-4.924655415,0.3843556112,5.148755132
+23.38738317,-1.940869507,-4.412745426,-0.3580162436,4.83399134
+23.39742417,-1.472550803,-4.301590734,-0.389696458,4.563326861
+23.40746517,-1.918198829,-4.899097821,0.3148982906,5.270655285
+23.41750617,-2.420645392,-4.956287683,0.459488824,5.53492924
+23.42754617,-1.266234722,-4.466033733,-0.335526098,4.654179352
+23.43758717,-1.40744922,-3.992935515,-0.08328247726,4.234546411
+23.44762817,-1.696937411,-4.768813085,-0.6098604995,5.098343324
+23.45766817,-2.359923666,-4.882609257,-0.8113087732,5.483368927
+23.46770917,-1.710645916,-4.533211225,-0.3680377865,4.859193891
+23.47775017,-1.580501806,-3.765841354,-1.107193673,4.231480224
+23.48779117,-1.965545488,-4.396247507,-0.681863113,4.8636713
+23.49783117,-1.719928371,-4.626726037,0.200869984,4.940151432
+23.50787217,-1.492339535,-4.206760882,-1.118080603,4.601523514
+23.51791317,-2.283327333,-4.172875683,-0.7159827858,4.810312519
+23.52795317,-1.714306712,-4.411386825,0.6985153985,4.784046926
+23.53799417,-1.827670482,-4.475491897,0.08151661813,4.834982117
+23.54803517,-2.11407763,-4.184268983,-1.206747782,4.840833746
+23.55807617,-2.103227098,-4.515792369,0.1795709163,4.98479595
+23.56811617,-1.705983493,-4.905384162,-0.03247952878,5.193671955
+23.57815717,-2.010610857,-4.754488576,0.423836596,5.179513017
+23.58819817,-1.932212851,-4.539106972,-1.118652461,5.058490085
+23.59823817,-2.399601556,-4.66740804,0.1761853784,5.251078625
+23.60827917,-1.57189719,-3.880838836,-1.011033288,4.307430691
+23.61832017,-2.677572194,-4.870090076,0.695143894,5.600928069
+23.62836017,-2.003014446,-5.149870282,-0.02369818032,5.525739081
+23.63840117,-2.56760858,-5.052152199,-0.8468949276,5.730103548
+23.64844217,-1.608480587,-4.269088401,-0.5860266638,4.599538327
+23.65848317,-2.610970654,-4.950000172,-0.1652452379,5.598836972
+23.66852317,-1.923097042,-5.693154384,1.40754526,6.171830582
+23.67856417,-2.22093038,-4.677273462,-0.9360883552,5.261718369
+23.68860517,-3.01530357,-4.694972984,-1.094849031,5.686257235
+23.69864517,-2.008653647,-5.445735886,1.164053167,5.919944982
+23.70868617,-1.797519461,-4.801871488,-0.5073167092,5.152321442
+23.71872717,-2.309004065,-4.955692436,-0.8138178134,5.527448483
+23.72876817,-1.911931783,-5.008548927,-1.143771515,5.481720421
+23.73880817,-1.470069245,-5.270693053,-0.5288321239,5.497360481
+23.74884917,-2.838734614,-4.754929456,-2.610425693,6.122261889
+23.75889017,-1.76623101,-4.453214006,-1.089570749,4.913028738
+23.76893017,-1.179187369,-4.210859196,-2.246790276,4.916287681
+23.77897117,-2.489687122,-4.391589323,-2.927248303,5.835527514
+23.78901217,-2.681724887,-4.798190958,-1.675371126,5.746403506
+23.79905317,-1.2821659,-4.725268578,-1.014512966,5.000134907
+23.80909317,-3.139741967,-4.898506667,-0.7817271245,5.870642595
+23.81913417,-1.985799951,-4.883936575,-0.361812256,5.284614085
+23.82917517,-1.930515404,-4.923616365,-0.1994508648,5.292321654
+23.83921517,-3.16698736,-5.318281787,0.7401633614,6.23392107
+23.84925617,-2.192968994,-5.030812785,1.586842527,5.712815374
+23.85929717,-2.317452853,-4.980817337,0.7713430542,5.547440778
+23.86933717,-3.764689452,-5.390891342,0.8851070666,6.634607045
+23.87937817,-2.35035806,-4.799391976,2.126340557,5.751492894
+23.88941917,-2.071946979,-4.818019159,-0.1642892182,5.247214866
+23.89946017,-3.371558047,-4.846137249,1.072057754,6.000146476
+23.90950017,-2.761156096,-5.22580164,0.3297794545,5.919606427
+23.91954117,-2.071531388,-4.667758873,-0.03041078389,5.106871841
+23.92958217,-3.448852391,-4.680549949,-0.8884376407,5.881449828
+23.93962217,-2.407698487,-5.059492208,0.3717887753,5.61548754
+23.94966317,-2.558023824,-4.746139044,-0.2518559504,5.397476552
+23.95970417,-2.992729517,-3.770993628,-1.544686441,5.055974594
+23.96974517,-2.071603894,-4.257358886,-0.7587083906,4.795027195
+23.97978517,-2.888111427,-5.202647835,0.2599572676,5.956199282
+23.98982617,-1.918923445,-4.364215875,-0.6530439413,4.811976079
+23.99986717,-2.305988656,-3.532987977,-1.806225965,4.589339818
+24.00990717,-2.390817868,-3.747038462,-1.584442829,4.718767466
+24.01994817,-1.412685109,-4.600237858,-1.015883553,4.918321559
+24.02998917,-3.27938634,-5.081388277,-0.8330341029,6.104820014
+24.04003017,-2.251136803,-4.371053317,-1.153530518,5.050183824
+24.05007017,-1.414218834,-4.397882973,-0.2505385727,4.626462918
+24.06011117,-3.507273969,-4.155113304,-1.67454316,5.689466764
+24.07015217,-1.610621691,-4.393556034,-0.9928431845,4.783636111
+24.08019217,-2.308095408,-4.561259733,-1.10876482,5.230846413
+24.09023317,-2.781292444,-5.091369474,0.02204400301,5.801561576
+24.10027342,-2.03176199,-5.106026689,-0.7120552111,5.541352539
+24.11031342,-3.01830056,-4.189748701,-0.4323934114,5.181804368
+24.12035442,-2.008109856,-4.16468198,-0.7054519504,4.677044327
+24.13039542,-2.423734184,-5.195288529,-0.2940471196,5.740380998
+24.14043642,-2.900170139,-5.673929908,0.9237776273,6.438775702
+24.15047642,-2.230305367,-4.111189604,0.7820995921,4.742132618
+24.16051742,-2.860744995,-3.455037576,-1.603255076,4.7635673
+24.17055842,-2.652837887,-4.793198605,1.135777202,5.59484509
+24.18059842,-2.264252547,-5.215860204,1.35582196,5.845535942
+24.19063942,-2.908338407,-4.062781968,-0.003781979084,4.99646314
+24.20068042,-2.73992047,-3.466119219,-0.6604026622,4.46735697
+24.21072042,-2.376519818,-4.077496194,1.33324703,4.90421954
+24.22076142,-2.63485039,-4.438900022,0.5170406288,5.187832013
+24.23080242,-3.136167564,-4.135640614,-0.9589468753,5.278129345
+24.24084342,-2.281212834,-3.628364543,0.2459046543,4.29295124
+24.25088342,-2.733085075,-3.594408007,-0.3983444899,4.533012385
+24.26092442,-2.550882912,-3.611475445,-1.286685652,4.604923288
+24.27096542,-2.312894657,-3.865788688,-1.231624761,4.670193082
+24.28100542,-2.215970917,-4.262704411,-0.9051600927,4.88881282
+24.29104642,-2.017378278,-4.048934007,-1.077941222,4.650337513
+24.30108742,-2.454285155,-3.166491809,-2.128232131,4.536469773
+24.31112842,-2.867519287,-3.620736265,-2.548887257,5.275341147
+24.32116842,-1.528499155,-4.016539848,-0.05189345419,4.297859344
+24.33120942,-2.092630481,-4.694706059,-1.191289498,5.276223837
+24.34125042,-3.151234084,-4.537302814,-0.5065758669,5.547432937
+24.35129042,-1.635471188,-3.77466948,0.4914865422,4.143000689
+24.36133142,-2.128990807,-4.153892113,-0.09827590764,4.668734271
+24.37137242,-3.002716269,-5.344183198,1.35367954,6.27766257
+24.38141242,-1.314017876,-5.843102136,2.438154441,6.46630363
+24.39145342,-2.274049703,-5.380544693,1.021281118,5.929972881
+24.40149442,-2.457233906,-4.185105427,0.3521854001,4.865916199
+24.41153542,-1.627239624,-4.497909245,1.634051192,5.054623593
+24.42157542,-2.564547562,-5.300606824,0.7525635517,5.93630262
+24.43161642,-2.539597785,-4.535048712,1.316322264,5.361802685
+24.44165742,-2.203807686,-3.602908105,-0.6746108115,4.277010039
+24.45169742,-1.981444945,-3.735022434,-0.1194744033,4.229750676
+24.46173842,-2.258621239,-3.235554442,0.2475962538,3.953667457
+24.47177942,-2.434657221,-2.941580705,-2.113200109,4.364180053
+24.48181942,-2.690563538,-3.660143867,-2.663471634,5.265915535
+24.49186042,-1.690036528,-4.684877766,-0.4047115231,4.996808438
+24.50190142,-2.698152347,-4.208831674,-1.548266691,5.233681294
+24.51194242,-2.642284833,-3.399336999,-1.959694911,4.730493137
+24.52198242,-2.052863275,-3.316744201,-2.766356902,4.782025745
+24.53202342,-1.915031831,-4.588931974,-0.7940021843,5.035482404
+24.54206442,-1.774962511,-5.116906604,-1.083776159,5.523386268
+24.55210442,-1.933964531,-4.52564025,0.7636463642,4.98044117
+24.56214542,-1.741549913,-3.972285196,-1.515683666,4.594490478
+24.57218642,-2.540533632,-4.910757169,0.3416919869,5.539548765
+24.58222642,-1.480158031,-5.439103974,1.211837783,5.765697759
+24.59226742,-2.089144664,-5.217393343,1.663996537,5.861279997
+24.60230842,-2.10823977,-4.129469755,-0.03320049047,4.636625675
+24.61234942,-1.432726879,-4.602423255,1.448425484,5.033184132
+24.62238942,-2.236949996,-4.89747054,0.9068148547,5.459988659
+24.63243042,-2.594977934,-4.520670117,0.9519424957,5.298732235
+24.64247142,-2.050588709,-3.877011833,1.080000027,4.516916522
+24.65251142,-1.967584997,-3.416666685,0.9353925365,4.052155125
+24.66255242,-2.49150853,-4.024638241,-0.8141815102,4.802938607
+24.67259342,-1.94062641,-4.196729692,0.6444923884,4.668398163
+24.68263342,-1.697932461,-4.01624661,0.09900271654,4.361537918
+24.69267442,-2.501440026,-3.273493516,0.4531247145,4.144669349
+24.70271542,-1.828687167,-3.62753073,-0.5212623185,4.09570389
+24.71275642,-1.730201929,-3.888122128,-0.1594184875,4.258697765
+24.72279642,-1.526493414,-4.245825838,-0.8990743107,4.600603635
+24.73283742,-1.447035308,-4.456589311,-0.606472038,4.724712457
+24.74287842,-0.6054220974,-3.900146342,-0.7673447281,4.020758055
+24.75291842,-1.342463411,-4.24191025,-1.169850097,4.600495607
+24.76295942,-1.252481048,-4.056909024,-1.906242589,4.65413584
+24.77300042,-0.6185037075,-3.889155331,-1.646633815,4.268428159
+24.78304042,-1.251824552,-4.511655757,-1.144183744,4.819881618
+24.79308142,-1.231571843,-4.540930426,-0.3000393462,4.714535179
+24.80312242,-1.37208102,-3.741328071,-0.4976711422,4.015945546
+24.81316342,-1.48495991,-2.980945038,-2.147856556,3.962881154
+24.82320342,-0.8220683809,-4.152964744,-0.6204626709,4.278771613
+24.83324442,-1.641427016,-5.731308051,0.279803887,5.968288267
+24.84328542,-1.089363831,-4.957567638,0.9466513503,5.163365106
+24.85332542,-1.574377286,-3.964186217,-1.830525239,4.641579349
+24.86336642,-1.617898112,-4.484750963,-0.08223641038,4.768369567
+24.87340742,-1.193060327,-5.237732883,0.803791008,5.431695747
+24.88344742,-1.288083428,-4.600518232,0.0007244700193,4.777439423
+24.89348842,-1.186545798,-4.589797654,-0.8979025286,4.824972786
+24.90352942,-1.637968095,-5.372355083,1.531402736,5.821540429
+24.91357042,-1.43421675,-4.834786634,0.8796638936,5.119174548
+24.92361042,-1.641802553,-4.242217229,0.6321389759,4.592550743
+24.93365142,-1.367606146,-4.832241049,0.4101494336,5.038762019
+24.94369242,-0.9965663259,-4.836764455,2.477098652,5.524803396
+24.95373242,-1.414390888,-4.414605718,-0.4512460041,4.657560325
+24.96377342,-1.709460978,-3.804771531,0.4370401937,4.193989433
+24.97381442,-0.6154961921,-3.754590141,0.4250995946,3.82837986
+24.98385442,-1.422316496,-3.95400183,-0.1174226153,4.20367729
+24.99389542,-1.354232833,-3.131097735,-1.282592016,3.644552356
+25.00393642,-1.192877236,-2.497267745,-1.228427503,3.027926092
+25.01397642,-0.5335526542,-2.630233429,-1.138642337,2.915358074
+25.02401742,-0.6182676993,-3.71999889,-0.05780615866,3.771470303
+25.03405842,-1.011415403,-3.091579328,-0.662101863,3.31951845
+25.04409942,-0.4315659938,-2.762589248,-0.7919234991,2.906078352
+25.05413942,-0.4196998006,-2.829239028,-0.9878186721,3.025975401
+25.06418042,-0.7040060071,-3.040516471,-0.6395403814,3.185808652
+25.07422142,-0.5183596145,-2.678727604,-1.041161651,2.920324614
+25.08426142,-0.4179293733,-2.774638313,-1.128336035,3.024305695
+25.09430242,-0.3901128528,-3.467960215,-0.7369777983,3.566801419
+25.10434404,-0.768591793,-3.173823048,0.5176089782,3.306328044
+25.11438404,-0.6441738613,-3.26394209,-1.354660703,3.592127997
+25.12442504,-0.8370841037,-3.407508191,-0.3309325254,3.524391891
+25.13446604,0.1231552072,-3.774123057,-0.1086500376,3.777694653
+25.14450704,-0.5320945048,-3.932517405,-0.4459683073,3.993332623
+25.15454704,-0.3718811248,-4.064696054,0.2563325787,4.089713434
+25.16458804,-0.5948951723,-4.301359476,-0.3798193413,4.358882465
+25.17462904,-0.7963139541,-4.529261431,0.3107315648,4.609216758
+25.18466904,-0.3494384148,-4.986035392,0.01853625834,4.998299684
+25.19471004,-0.6846706536,-5.039608167,0.6029970378,5.121526121
+25.20475104,0.2243134816,-4.369664603,0.5080850333,4.404819597
+25.21479104,-0.5236870857,-4.854552855,-0.353494007,4.895496869
+25.22483204,-0.457056967,-5.27128713,0.921018911,5.370627981
+25.23487304,-0.002341691097,-4.388998421,1.140729793,4.534818308
+25.24491404,0.04624596664,-4.157084985,-0.6343234956,4.205456046
+25.25495404,-0.5029607162,-5.11547462,-0.196974569,5.143913788
+25.26499504,0.4473983535,-4.932857305,-0.1150240874,4.954440132
+25.27503604,-0.862834876,-4.117986116,-0.1255239326,4.209281403
+25.28507604,-0.08187285975,-3.339001335,-1.205425726,3.550870916
+25.29511704,0.2265282059,-3.977747957,0.05366282165,3.984554371
+25.30515804,-0.7609547447,-3.938385671,-0.4674299276,4.038369046
+25.31519804,0.1007097198,-2.997711052,-0.8485841882,3.117131554
+25.32523904,-0.5007957481,-3.78091109,-0.6992474699,3.87750333
+25.33528004,-0.4569049394,-4.09292378,0.1943947774,4.122933
+25.34532004,0.5836521095,-3.489915048,-0.2460660374,3.546928998
+25.35536104,-0.4799670523,-3.162406359,-1.311721675,3.457136981
+25.36540204,-0.2702131194,-3.377366087,0.04907743514,3.388513746
+25.37544304,0.3676664517,-3.776160227,-0.2933548093,3.80534121
+25.38548304,-0.9033663862,-3.297580244,-0.7410667562,3.498469127
+25.39552404,-0.1893721288,-3.069108186,-0.5318650746,3.120603679
+25.40556504,-0.4508447389,-3.587444558,0.6721462101,3.677607913
+25.41560504,-0.3643602167,-3.853079472,-0.07999400318,3.871095301
+25.42564604,0.05810130601,-3.687020302,-0.08093715906,3.688366209
+25.43568704,-0.4846410241,-3.86359949,-0.1404004186,3.896407348
+25.44572704,-0.2424487305,-3.416460863,-0.2660313553,3.435368815
+25.45576804,-0.6324068514,-2.917638404,-0.6864362204,3.063290219
+25.46580904,-0.1919090164,-3.139053749,-1.055676194,3.317369401
+25.47584904,-0.6919214934,-3.645905313,0.1332311475,3.713371977
+25.48589004,-0.03380842731,-3.164802841,-0.1089967775,3.166859695
+25.49593104,-0.1255323014,-2.776060941,-0.5796783417,2.838714442
+25.50597204,-0.5703933287,-3.261645596,-0.9255119115,3.438059458
+25.51601204,-0.4342532645,-3.398806657,0.7978069675,3.518090184
+25.52605304,0.0129882374,-3.381014749,-0.6706961006,3.446920754
+25.53609404,-0.7783793011,-3.387092637,-0.392224794,3.497443518
+25.54613404,-0.1648566905,-3.744615376,0.3385093474,3.763497126
+25.55617504,-0.1707112517,-3.526536452,-0.5066331697,3.566830364
+25.56621604,-0.4203786623,-2.766467414,-0.619118396,2.865897374
+25.57625604,-0.05263294425,-3.589352797,-0.6398608088,3.646319457
+25.58629704,-0.04983390039,-4.247661864,0.5814190578,4.287559078
+25.59633804,0.1384662054,-3.998470489,-0.2696981442,4.009947161
+25.60637804,-0.1272673439,-3.507401438,-1.045730665,3.662187113
+25.61641904,-0.08280556373,-3.783243837,0.5557445186,3.824740862
+25.62646004,0.5175241204,-3.69042689,-0.2001402515,3.731908086
+25.63650104,-0.5448105543,-3.47885884,0.09302861631,3.522489417
+25.64654104,0.02767063245,-4.17533356,-0.2268310368,4.181582036
+25.65658204,-0.2240093167,-4.152906857,1.524534597,4.429562199
+25.66662304,-0.2447347909,-3.599357968,0.3807344306,3.627703351
+25.67666304,-0.4041670742,-2.881165227,-0.2265456927,2.918182146
+25.68670404,0.2452523243,-3.809069819,0.4657529461,3.845268182
+25.69674504,0.0356650736,-4.202253849,1.056762022,4.33323844
+25.70678504,-0.2195676255,-3.411047511,0.06328616917,3.418692762
+25.71682604,-0.029784474,-3.071875381,-0.7729130316,3.167759465
+25.72686704,0.05751113009,-3.271794608,0.3675518829,3.292877446
+25.73690704,-0.0175920061,-3.553244486,-0.3404085231,3.56955653
+25.74694804,0.09307625284,-3.093924062,-0.9045122212,3.224774666
+25.75698904,-0.3217393137,-2.909051183,-0.4270508105,2.957780818
+25.76703004,-0.05136979949,-2.943005672,-0.5043989486,2.98635891
+25.77707004,-0.3580371474,-2.637155947,-0.4303743678,2.695923624
+25.78711104,-0.02624977732,-2.88228263,-0.8514937627,3.005542187
+25.79715204,0.09923996732,-3.32647046,-0.473548454,3.361473253
+25.80719204,-0.2382335459,-2.984755669,-0.335351851,3.012969049
+25.81723304,0.491520383,-2.884415109,-1.037657415,3.104541145
+25.82727404,-0.538180835,-3.086522949,-0.3234983754,3.1497482
+25.83731404,0.1040243693,-3.136638849,0.147611205,3.14183281
+25.84735504,-0.06956218673,-2.834215009,-0.5500709653,2.887939002
+25.85739604,-0.7177320535,-3.109474147,-1.528628817,3.538456561
+25.86743604,0.6675504448,-3.169558966,0.2307685518,3.247303768
+25.87747704,-0.2215027067,-3.299746345,-0.5132504636,3.346761932
+25.88751804,-0.0127233494,-2.912794863,-0.41437814,2.942149731
+25.89755904,0.7489069223,-3.341489618,-0.3903203559,3.446558345
+25.90759904,-0.289294923,-3.423228723,-0.7888309067,3.524832001
+25.91764004,0.05818023428,-3.04719633,-0.1986585671,3.054219318
+25.92768104,-0.02677535065,-2.622944874,-0.9200734162,2.779764707
+25.93772104,-0.1011250457,-3.024053928,-0.464039712,3.06112092
+25.94776204,0.5238869509,-3.576552072,0.6261449951,3.668547372
+25.95780304,0.3680841257,-2.970760358,-0.5418854481,3.042128016
+25.96784304,-0.419536042,-3.046032442,0.02703167796,3.07490729
+25.97788404,0.1572111636,-3.268055021,1.08787915,3.447953018
+25.98792504,0.0669886718,-2.703868877,-0.3569368476,2.728149245
+25.99796504,-0.4309278433,-3.133507081,0.4407794881,3.193564151
+26.00800604,-0.09530889337,-3.613633945,1.689728379,3.990315284
+26.01804704,0.5034032043,-2.49850063,1.015769532,2.743666876
+26.02808704,-0.8572613101,-2.244710421,-0.4336990947,2.441662698
+26.03812804,0.06149665623,-3.443693393,1.909850321,3.938316172
+26.04816904,0.2466045294,-2.836430519,1.273059885,3.11878716
+26.05821004,-0.8760389853,-2.529511338,-0.2323022765,2.6869753
+26.06825004,0.6277627735,-2.51669892,1.042096036,2.795321752
+26.07829104,-0.3513821754,-2.278076826,0.3097889936,2.325741318
+26.08833204,-0.164511321,-2.505921039,-0.3607217503,2.537089752
+26.09837204,0.5986757992,-2.300222717,-0.07768610716,2.378123712
+26.10841292,-0.333353163,-1.912962794,-0.4739343703,1.998790827
+26.11845392,0.583904161,-1.724447976,-1.136502256,2.146229781
+26.12849392,-0.4322627992,-2.236577236,-0.6353724861,2.364915867
+26.13853492,0.7419382837,-1.941896425,-0.1800129658,2.086585443
+26.14857592,-0.02062215202,-1.266475335,-0.9596409398,1.589117926
+26.15861592,-0.159061716,-1.9280777,-0.2645438236,1.952630964
+26.16865692,0.4892872582,-2.04489469,-0.2964374614,2.123410342
+26.17869792,-0.1973144384,-1.158141413,-0.1654878974,1.186427732
+26.18873792,-0.1542195819,-0.7220680562,-1.311571401,1.505119762
+26.19877892,0.2938272278,-1.274907313,0.4904983628,1.397251495
+26.20881992,0.1933406158,-1.630451353,-0.05244835496,1.642712099
+26.21886092,-0.09130808224,-1.170167454,-0.01044722021,1.173770924
+26.22890092,0.5727120421,-0.8381730746,0.1710351509,1.029459183
+26.23894192,0.04337175865,-1.360774113,-0.2065879762,1.377049704
+26.24898292,0.2408132461,-1.556193615,0.4194640481,1.629625624
+26.25902292,0.343412859,-1.149353413,-0.5482390326,1.318905492
+26.26906392,0.04861353166,-0.85430832,-0.8205444503,1.185537505
+26.27910492,0.6005043697,-1.256341964,0.5540330386,1.498650472
+26.28914492,0.5022588676,-1.405991509,0.01099042654,1.493049524
+26.29918592,-0.02022117921,-1.038967922,-1.085006998,1.502365942
+26.30922692,0.3244714983,-0.6194527106,-0.2421127349,0.7400148581
+26.31926692,0.4193105587,-0.9463379395,-0.4326723236,1.121865491
+26.32930792,0.3426472027,-1.296674158,-0.2774123758,1.369572416
+26.33934892,0.5270231415,-0.8317632106,0.1859484744,1.002077974
+26.34938892,0.3556449053,-0.4998080803,-0.7805103189,0.9927173684
+26.35942992,0.2026931824,-0.04305151395,-0.6114439255,0.6456017604
+26.36947092,0.2950400499,-0.7058055608,0.6438141114,0.9998533546
+26.37951092,0.3347260162,-0.3761918749,-1.277907227,1.373538755
+26.38955192,0.09136108177,-0.1276978725,-0.1854847902,0.243018932
+26.39959292,0.6602053186,-0.8500127361,-0.4576440275,1.169542975
+26.40963392,0.4864712392,-0.6621251057,0.192146523,0.843791567
+26.41967392,0.6317459699,-0.4329380064,0.05163500726,0.7675965489
+26.42971492,0.4912171318,-0.6285259813,-0.6790745759,1.047607493
+26.43975592,0.5894802852,-0.4010580365,-0.3781417751,0.8070475558
+26.44979592,0.6887817579,-0.406025831,-0.3074372435,0.8566183188
+26.45983692,0.5893090714,-0.5428899997,-0.5571852726,0.9759457779
+26.46987792,0.8219367454,-0.4644829674,-0.249298963,0.9764601443
+26.47991792,0.8652900488,-0.4828222843,-0.5183322787,1.118263197
+26.48995892,0.4833961885,-0.8207862327,-0.5644931227,1.107255346
+26.49999992,0.9632991041,-1.259726771,0.1626631075,1.594150554
+26.51003992,0.7364734029,-1.103829696,0.451120289,1.401550066
+26.52008092,0.639442806,-0.6914415101,-0.9148068291,1.312954683
+26.53012192,0.8671865201,-0.3680208296,0.3127587944,0.9926076038
+26.54016192,0.4075564127,-0.8988280698,0.809713068,1.27656938
+26.55020292,0.6535992075,-1.547769385,0.3180049163,1.709944186
+26.56024392,0.6746523998,-1.539970515,0.1168454951,1.685324277
+26.57028392,0.7542032571,-1.008145786,0.08676157057,1.262025376
+26.58032492,1.074880936,-1.046533415,-0.7818832451,1.691727704
+26.59036592,0.5851637975,-1.541103706,-0.1501494813,1.655283108
+26.60040692,1.065584448,-1.358054135,0.06995667279,1.72762125
+26.61044692,0.716407586,-1.207369341,-1.384085062,1.971464433
+26.62048792,0.6710396245,-1.160234716,0.2414058065,1.361879414
+26.63052892,0.4434499115,-1.580564664,1.672029442,2.343184785
+26.64056892,0.4107758166,-1.461498542,0.6863736552,1.666080297
+26.65060992,0.06726485224,-1.010356326,1.303601062,1.650672649
+26.66065092,0.4516340034,-1.459635619,1.306329373,2.010225322
+26.67069092,0.4883123081,-1.835044406,0.7953207314,2.058730664
+26.68073192,0.5959444186,-1.401950206,0.2723749995,1.547514869
+26.69077292,0.8759031837,-1.250975536,-0.4415805566,1.589697948
+26.70081292,0.6038772995,-1.59420958,-0.585990411,1.802652695
+26.71085392,0.49272374,-1.311454457,-0.1184640044,1.405959885
+26.72089492,0.5843451507,-0.5606637446,-1.111765026,1.375436135
+26.73093492,0.5145915225,-1.469449878,-0.4051945031,1.608810109
+26.74097592,0.727282457,-1.93967536,0.9968730855,2.298920665
+26.75101692,0.6085555471,-1.557687579,-0.0403972435,1.67283065
+26.76105692,0.5326251396,-1.134335498,-1.045796739,1.632206292
+26.77109792,0.9078137784,-1.867512679,0.4598554444,2.126780781
+26.78113892,0.216505658,-1.999750823,0.1672952718,2.018381966
+26.79117892,0.2882659775,-1.32985199,-0.7156641126,1.537458524
+26.80121992,0.6337165546,-1.569536669,-0.4588912386,1.753745476
+26.81126092,0.5710996724,-1.788604357,0.9710237145,2.11379929
+26.82130192,0.3051529556,-1.758324551,-0.1574064606,1.791535751
+26.83134192,0.4080715524,-1.612065222,-0.2818790638,1.686633475
+26.84138292,0.4791251994,-1.599502187,0.2379156035,1.686585912
+26.85142392,0.2919545108,-2.000012924,-0.1429696852,2.02625997
+26.86146392,0.2561818301,-2.093044172,-0.1644593722,2.115067356
+26.87150492,0.6748570523,-1.898508477,0.2143232578,2.02625293
+26.88154592,0.3100058888,-1.470903935,-0.2328671175,1.521147307
+26.89158592,0.4893191987,-1.457272029,-0.7545937049,1.712450497
+26.90162692,0.4920024494,-2.432266295,-0.132852248,2.485082586
+26.91166792,0.2840914858,-2.360462925,0.7685048157,2.498618187
+26.92170792,0.6412422866,-1.561614276,0.01954314888,1.688257312
+26.93174892,0.6489276476,-1.731451479,-0.4277875596,1.897902398
+26.94178992,0.9363060909,-2.11988757,0.2663067591,2.332704802
+26.95182992,0.3104147553,-2.010137671,-0.00524495244,2.033971063
+26.96187092,0.2458104775,-1.319149685,-0.5277229071,1.441898106
+26.97191192,0.8409459704,-1.607789738,0.536360414,1.892051918
+26.98195192,-0.1498469062,-2.295496413,0.2863486755,2.318135768
+26.99199292,0.1746313164,-1.972391555,-0.1174161834,1.983585416
+27.00203392,0.9750667718,-1.99996527,0.1890609473,2.233015972
+27.01207392,0.1551372293,-2.547700565,0.7848524612,2.670363105
+27.02211492,1.361616258,-2.555714758,0.4947896343,2.937770165
+27.03215592,0.3902835184,-2.521732203,-0.0226374954,2.551855596
+27.04219592,0.7159148119,-2.014339918,-0.1625455785,2.143949717
+27.05223692,0.6820309281,-1.769855553,-0.4600665289,1.951721311
+27.06227792,0.3307192117,-2.218929462,-0.594745447,2.320936299
+27.07231892,0.3001282422,-2.516032337,0.5113436866,2.584950299
+27.08235892,0.310817665,-2.480822451,0.907900098,2.659956812
+27.09239992,0.6727568056,-2.374313956,-0.2866106308,2.484373992
+27.10244092,0.3348995323,-2.342543987,0.564830507,2.432838574
+27.11248092,1.042793097,-1.900052142,0.2075638765,2.177314481
+27.12252192,0.2669198762,-1.49668387,-0.5429584122,1.614345894
+27.13256292,0.03238526984,-2.159518535,0.2928800154,2.179529264
+27.14260292,0.2150491531,-2.31305794,1.808502286,2.944004703
+27.15264392,-0.1889739882,-2.006265352,0.177206887,2.022922172
+27.16268492,0.1179030371,-1.512138792,-0.06352473557,1.51805805
+27.17272492,0.7642905812,-2.184928196,0.2627803034,2.329614732
+27.18276592,0.2335520092,-2.199343337,0.8997134113,2.387706405
+27.19280692,0.6823174417,-1.592187174,0.1473808247,1.73848733
+27.20284692,0.1434895027,-1.936715938,-0.2309042072,1.9557031
+27.21288792,0.2917466423,-1.947168567,0.1831283623,1.977401711
+27.22292892,0.1906598319,-1.988882311,0.1419534391,2.003036394
+27.23296892,0.461682005,-1.825672927,-0.5860319263,1.972223448
+27.24300992,0.4523112572,-1.964271526,0.7097882456,2.136994959
+27.25305092,0.1228937819,-2.095995554,1.183812663,2.410334555
+27.26309092,0.3100265733,-1.945464396,-0.3914020908,2.008517809
+27.27313192,0.03098852534,-1.794410204,-0.1050920069,1.797752096
+27.28317292,-0.2047359072,-1.786785727,0.7285963994,1.940456838
+27.29321292,0.456953252,-2.082829671,0.1471358263,2.13743647
+27.30325392,0.02809424495,-2.164400961,-0.2280338091,2.17656156
+27.31329492,0.004736664947,-1.645472558,1.097848653,1.978098592
+27.32333492,0.4198143695,-1.156891132,-0.02546871722,1.230971101
+27.33337592,-0.2409663883,-1.953531214,-0.555439294,2.04520459
+27.34341692,0.3298784551,-2.00724403,0.5819973475,2.115790468
+27.35345692,0.4110444231,-1.592647642,0.3442565757,1.680475118
+27.36349792,-0.1367656615,-1.292802424,-0.2813650936,1.330116262
+27.37353892,0.3379258684,-1.368094389,0.4155148387,1.469193224
+27.38357992,0.1365369257,-1.886660117,0.2575528926,1.909047465
+27.39361992,0.02330254537,-1.712525357,-0.6313496017,1.825346112
+27.40366092,0.5299299386,-1.124160831,-0.4799154872,1.332247045
+27.41370192,0.3278608734,-1.344722483,-0.3537892914,1.428614073
+27.42374192,0.4627945108,-1.536725749,-0.7672751462,1.778880529
+27.43378292,0.2622916589,-1.755186497,-0.8168495947,1.953642703
+27.44382392,0.304600814,-1.550379144,-0.9438125271,1.840445389
+27.45386392,0.5724444954,-1.207779084,-0.8207906181,1.56847705
+27.46390492,0.582682897,-1.574992267,-0.5034733343,1.7531701
+27.47394592,-0.3622150926,-1.954823888,1.07420719,2.259747174
+27.48398592,0.8389848143,-1.314282609,0.1762169534,1.569167521
+27.49402692,0.1883062362,-2.050568097,-0.3374550945,2.086663533
+27.50406792,0.5375611032,-2.36048266,0.02444779336,2.421042755
+27.51410792,0.7871097788,-1.966342902,0.7148145121,2.235398399
+27.52414892,-0.3236611473,-1.197212142,-1.89923704,2.268297773
+27.53418992,0.6464130525,-1.151767436,0.2875175339,1.351696857
+27.54422992,0.6222201978,-2.070713655,0.2267146772,2.174031408
+27.55427092,-0.4010434185,-2.299788415,-0.2889822614,2.352312336
+27.56431192,0.8505202013,-1.973575616,-0.4609874654,2.197929655
+27.57435192,0.5570499095,-1.114727079,-0.5684756613,1.369702756
+27.58439292,-0.04249546202,-1.136344016,-0.9482593346,1.48063478
+27.59443392,0.6876843817,-1.901870187,0.269553718,2.040264499
+27.60447392,0.5622058747,-2.261583293,-0.03165741026,2.330630092
+27.61451492,0.3430204378,-1.901485294,0.1561586648,1.938477463
+27.62455592,0.1572127351,-1.404857588,-0.2636532927,1.438003388
+27.63459592,0.3575869483,-1.385497018,-0.3379585397,1.470267454
+27.64463692,-0.05870800031,-1.401964239,-0.08188031495,1.40557986
+27.65467792,0.2718894431,-1.566248195,0.3585804999,1.629612608
+27.66471792,0.5129471393,-2.19679205,0.4977296144,2.310139573
+27.67475892,-0.04246024168,-2.15611414,1.106335301,2.423759241
+27.68479992,0.1760781917,-0.9770216422,0.8066187215,1.27914369
+27.69483992,0.04849063507,-0.9806003574,-0.42942478,1.071603492
+27.70488092,-0.02389069076,-2.248632587,1.309426643,2.602213944
+27.71492192,0.2315271732,-2.329307352,1.715486534,2.902097797
+27.72496192,0.1975516343,-1.592876122,-0.5703122717,1.703389878
+27.73500292,0.08293590182,-1.452611798,-0.311436739,1.487935564
+27.74504392,0.6236173169,-1.762308405,0.870004878,2.061925789
+27.75508392,0.1043168306,-1.657620733,-0.4326419181,1.716323841
+27.76512492,0.03491663,-1.647841265,-1.111110722,1.987754271
+27.77516592,0.8234277854,-1.950208827,-0.2727638394,2.134419803
+27.78520592,0.1642398458,-2.146359377,-0.5201004767,2.214573956
+27.79524692,-0.355324624,-1.430507568,-0.8157848167,1.684669807
+27.80528792,0.6629223736,-0.8559421782,-0.2979027736,1.122875393
+27.81532792,0.06254793992,-1.380684759,-0.6128922808,1.511899335
+27.82536892,0.191213417,-1.718192333,0.6907204753,1.861677265
+27.83540992,0.4237046682,-1.848459234,-0.307421456,1.921154637
+27.84544992,-0.1516177902,-0.8414369173,0.0616846168,0.8572100279
+27.85549092,0.389661192,-0.8336277415,-0.4523815334,1.025387784
+27.86553192,-0.4219149086,-1.708680959,-0.2454047173,1.777027374
+27.87557192,0.4776458173,-1.504709758,0.3242801481,1.611662061
+27.88561292,-0.08985233568,-1.14627997,-0.3957541734,1.215998593
+27.89565392,0.07512140874,-0.7219942351,-0.1789049184,0.7476134506
+27.90569392,0.5229126951,-1.68252461,0.3608381099,1.798480161
+27.91573492,-0.01506928087,-1.219035048,0.2951083893,1.254337471
+27.92577592,-0.04226109831,-0.6536859655,-0.6597822726,0.9297332893
+27.93581692,0.1690862556,-0.6722111873,-0.6743330687,0.9670486698
+27.94585692,0.03845405385,-1.63344352,0.5255424803,1.716336606
+27.95589792,0.004374921012,-1.716866915,0.351431694,1.752471221
+27.96593892,0.06698496704,-0.8829131182,-0.2500474066,0.9200794888
+27.97597892,0.8012295621,-0.8374026308,-0.7163570076,1.362490125
+27.98601992,0.1871350206,-1.721964664,-1.038519294,2.01958019
+27.99606092,0.1782277378,-1.9830617,0.06870419919,1.992239719
+28.00610092,0.3632566279,-1.35802636,-0.05555088758,1.406867753
+28.01614192,-0.1032793883,-0.7437857846,-0.6215666252,0.9747968994
+28.02618292,0.6265843403,-1.508148213,-0.7361024702,1.791358651
+28.03622292,0.3186709507,-1.734214142,0.3561562443,1.798859954
+28.04626392,0.3865006623,-1.389372114,-0.185592379,1.454022752
+28.05630492,0.03445360817,-1.659683777,-0.1943018067,1.671373831
+28.06634492,0.1494683812,-1.293494588,0.8618784177,1.561506789
+28.07638592,0.2760116936,-0.9057837714,-0.3883410734,1.023442956
+28.08642692,-0.1659622162,-1.272964721,-0.8796598005,1.556208214
+28.09646692,0.8135934265,-2.304241947,0.4459384865,2.48401416
+28.10650796,0.4611282736,-2.096134718,0.1609048498,2.152280282
+28.11654896,0.1420752622,-1.210350251,-0.7167563725,1.413814984
+28.12658896,-0.2022125778,-0.8907075298,-0.5770020711,1.080361616
+28.13662996,0.651448163,-1.509100725,0.2143665272,1.657625626
+28.14667096,-0.05935062759,-1.715961912,-0.1869758302,1.7271386
+28.15671096,0.3122174884,-1.360574577,-0.2877432364,1.425285624
+28.16675196,0.8224836794,-1.211286683,-0.07460462451,1.466035702
+28.17679296,-0.5271190724,-1.276712787,0.2042467511,1.396268882
+28.18683296,0.312542484,-1.124487544,0.3257764506,1.211728244
+28.19687396,0.1293859637,-1.554424832,-0.1703048337,1.569070114
+28.20691496,-0.4025720999,-1.438289482,0.9033971572,1.745527815
+28.21695496,0.6169145805,-1.267946787,-0.07572436631,1.412093069
+28.22699596,0.09225393333,-1.540699517,-0.4203200805,1.599667078
+28.23703696,0.9623283932,-1.365425719,0.4216760498,1.722867964
+28.24707696,-0.1272676545,-1.121337576,-0.7535236645,1.356979339
+28.25711796,-0.1786208351,-0.7042562679,-1.002011619,1.237703348
+28.26715896,0.1727706045,-1.432396365,0.3852952588,1.493339032
+28.27719896,0.0341501788,-1.53665646,1.186575472,1.941762257
+28.28723996,0.1238267965,-1.608021142,0.0944354564,1.615544219
+28.29728096,0.4213198448,-1.118933054,0.3023449033,1.233261543
+28.30732096,0.2891949539,-0.483566781,-0.465410884,0.7308062972
+28.31736196,-0.6161583893,-0.7478004098,-1.597669816,1.868530293
+28.32740296,0.5293625394,-1.620580669,0.8078220785,1.886553183
+28.33744296,0.1275352286,-1.629961211,0.2890009725,1.660289235
+28.34748396,-0.178131076,-0.5139163884,0.6166660738,0.8222638148
+28.35752496,0.5946131903,-0.407458143,-0.7471519536,1.038182559
+28.36756496,-0.1932730622,-1.225336738,0.315193575,1.27990296
+28.37760596,0.01385000507,-1.034347306,0.4544087631,1.129846669
+28.38764696,0.08383398847,-0.8302033927,0.1466469991,0.8472137589
+28.39768696,0.1229775889,-1.485118224,-0.07984314501,1.492338619
+28.40772796,-0.1675385159,-1.211951219,1.386207601,1.848909523
+28.41776896,0.1993217875,-0.648761002,-0.7372777605,1.002097056
+28.42780896,0.01906654141,-1.010124777,-0.9868158746,1.412275174
+28.43784996,0.2885932389,-1.813749285,1.179026717,2.182447371
+28.44789096,-0.009540334189,-1.565487911,0.1921219647,1.577261635
+28.45793096,0.07095420321,-0.643435358,-1.082486263,1.261277158
+28.46797196,-0.06376631694,-0.7705864976,-0.1698417342,0.7916539067
+28.47801296,-0.1619338684,-0.8647545169,0.4856428349,1.004923836
+28.48805296,0.3982997953,-0.9553544922,-0.4849359065,1.143025707
+28.49809396,-0.1333039454,-1.065333602,0.1639617741,1.086088895
+28.50813496,0.6267384875,-1.065351436,0.3158969951,1.275760842
+28.51817496,0.3076792451,-0.4846545458,-0.1933370161,0.605752217
+28.52821596,-0.8205244236,-0.238975923,-1.896649647,2.080300388
+28.53825696,1.292888816,-0.9867106247,-0.1129629439,1.630312846
+28.54829696,0.5485216359,-1.597548779,-0.4855410933,1.757494876
+28.55833796,0.01180718549,-0.9386891967,-0.9721843868,1.351450813
+28.56837896,0.9547536908,-0.4362514408,-1.170528958,1.572262056
+28.57841896,-0.4660909152,-0.604176677,-0.5801695079,0.9585754306
+28.58845996,0.5278849846,-1.061853705,-0.6430475414,1.348964784
+28.59850096,-0.6199937242,-1.78688206,0.5336420435,1.96522608
+28.60854096,0.2719015943,-0.901775505,1.848945723,2.075025259
+28.61858196,0.647244892,-0.3698352571,0.7886888194,1.085234593
+28.62862296,-1.172865213,-0.8278001871,0.5612946957,1.541401211
+28.63866296,0.06098317933,-1.091406702,2.540770737,2.765936275
+28.64870396,-0.4706954513,-0.861616901,0.3921294844,1.057214938
+28.65874496,-0.7308375641,-1.237282234,0.5929959601,1.554553016
+28.66878496,0.7257997493,-1.27779993,1.67269544,2.226537216
+28.67882596,-0.182230431,-0.8889891793,1.03785622,1.37864253
+28.68886696,0.1265350532,-0.02810885386,-0.6114205366,0.6250090399
+28.69890696,0.1773075505,-0.6043106148,0.09450386882,0.6368361389
+28.70894796,-0.3943200341,-0.9068357585,-0.02465069175,0.9891648189
+28.71898896,0.8059510425,-0.6350621451,-0.4097997701,1.104896766
+28.72902896,0.230205666,-0.7970589624,-1.09717213,1.37553056
+28.73906996,0.3904104396,-0.08785514608,-0.4671323043,0.6151027782
+28.74911096,0.5387151609,0.5277407045,-0.6546916866,0.9986718582
+28.75915096,-0.002368665948,-0.4428097875,-1.215580001,1.29372364
+28.76919196,0.2850597299,-1.255539434,0.02833034456,1.287804694
+28.77923296,0.6581240022,-0.6142624296,0.1443437809,0.9117459415
+28.78927296,0.09627471635,0.1184024899,-1.045376909,1.056456744
+28.79931396,-0.2061571278,-0.6322295346,1.502029833,1.642652905
+28.80935496,-0.3904984036,-0.4169308516,2.411095281,2.477841963
+28.81939496,-0.6406786881,0.03759336883,1.070331071,1.247994809
+28.82943596,0.2464873658,-0.9969251257,1.71115784,1.995664521
+28.83947696,-0.5511187498,-1.754028309,2.787875825,3.339550688
+28.84951696,-0.6934764873,-0.6993174903,1.186666104,1.542119008
+28.85955796,0.1460402135,0.2175691386,-0.1168051493,0.2868928666
+28.86959796,-0.1597444515,-0.688123069,0.5304751915,0.883422649
+28.87963896,-0.5652068119,-1.53881072,1.433427376,2.177638908
+28.88967996,0.5260995738,-1.191155962,0.3881855375,1.35879406
+28.89971996,-0.8695231406,-0.3462872772,-0.7691602886,1.211442495
+28.90976096,0.3274641398,0.23416752,-0.2556735975,0.4769026931
+28.91980196,0.2614392993,-0.5787423852,-0.2307755685,0.6756852956
+28.92984196,0.2653422244,-1.333796522,0.005333245397,1.359944154
+28.93988296,1.024388109,-0.464836322,0.2020727563,1.142924846
+28.94992396,-0.08848828076,0.2100979501,-1.081296355,1.105067025
+28.95996396,0.02335996457,-0.6191965295,0.8449653465,1.047815092
+28.97000496,0.06068106101,-1.028683474,1.170731272,1.559642136
+28.98004596,0.2461537822,-0.3927023288,0.05260272145,0.4664481213
+28.99008596,0.5827615786,-0.4902176964,-0.7676365042,1.081291011
+29.00012696,0.01427041302,-0.7032178755,0.3890456629,0.8037882513
+29.01016796,0.7994804406,-0.3887389764,-0.8868395966,1.255695599
+29.02020796,-0.5368804508,0.01105839585,-1.628055457,1.714330037
+29.03024896,0.2890995346,-0.8236257868,-0.8259730053,1.201735987
+29.04028996,0.2021379162,-0.3877980863,-0.4830022323,0.6515659977
+29.05032996,0.5419051825,0.6059895696,-2.037198,2.193412929
+29.06037096,0.1959608445,-0.5171474867,-2.85940189,2.912391001
+29.07041196,0.5743714819,-1.663367377,-0.6254275417,1.867579514
+29.08045196,0.1465822778,-0.3853695549,-0.9879718691,1.070553349
+29.09049296,0.1123635221,0.7286780412,-3.216837505,3.300248594
+29.10053396,0.6443365601,-0.1091200259,-0.7827462941,1.019690416
+29.11057329,-0.2500975099,-0.9935858539,1.11651238,1.515375039
+29.12061429,0.09527421207,-0.1284574989,-0.5510351712,0.5737754477
+29.13065529,0.5914729432,-0.4047714205,-1.112842668,1.323668746
+29.14069529,0.384286943,-1.074177296,0.8565796709,1.426626108
+29.15073629,0.3776570044,-0.3455672291,1.300368721,1.397497883
+29.16077729,-0.5302735722,0.4429597321,-0.9110114014,1.143391953
+29.17081729,-0.01026653211,-0.1661358785,0.7271638316,0.745971695
+29.18085829,0.1043866774,-1.227843951,1.44430729,1.898557582
+29.19089929,-0.2528998245,-1.095678751,0.7989810884,1.379435039
+29.20093929,-0.02671874229,-0.01530313181,0.3626302814,0.3639351564
+29.21098029,0.06776102504,-0.1061355065,0.6400064045,0.6522763985
+29.22102129,-0.05926942438,-0.5750786296,1.31195264,1.433683376
+29.23106129,-0.2185071599,-0.4089101893,0.9715458709,1.076500953
+29.24110229,-0.5397653208,-0.4203918551,0.527718814,0.864038807
+29.25114329,0.2464996085,-0.5374526008,0.6627526581,0.8881770324
+29.26118329,-0.5480929984,-0.3696927312,0.928595733,1.139898542
+29.27122429,0.03708027338,-0.0455838791,0.4380605328,0.4419840123
+29.28126529,0.6229568738,-0.4067145233,0.7812955999,1.078848824
+29.29130529,-0.246560785,-0.7874676284,1.44921018,1.667665324
+29.30134629,0.03144227841,-0.7710585871,0.6250311005,0.9930678921
+29.31138729,-0.1000107034,-0.5479586952,0.7036252803,0.8974126183
+29.32142729,0.06639228322,-0.02562838275,-0.236404683,0.2468844333
+29.33146829,-0.4553340118,0.4202718044,-0.9367759877,1.123168154
+29.34150829,0.4371735833,-0.07988729149,-0.1682471985,0.4751945297
+29.35154929,0.3628923098,-0.9737438393,0.2056898439,1.059328186
+29.36159029,-0.2007064447,-0.9819705062,-1.169492832,1.540215126
+29.37163029,1.158081479,0.1812031848,-0.5818283629,1.308629646
+29.38167129,-0.4558420618,0.6263195345,-2.160880644,2.295533337
+29.39171229,-0.599684115,0.1268699708,-1.029659008,1.198296583
+29.40175229,0.4609173353,-0.1249825444,0.1433023918,0.4985990392
+29.41179329,-0.274229243,-0.6787469126,-0.7365673238,1.03847507
+29.42183429,0.2383867795,-0.143226378,-0.01818951845,0.2786986016
+29.43187429,0.3442292765,0.1936162937,-0.4367063177,0.5888068205
+29.44191529,-0.759664118,0.2003696999,-0.6124397063,0.9961525901
+29.45195629,0.2422401494,0.1696431481,-0.4170701981,0.5112794126
+29.46199629,0.1635936919,-0.6171032263,-0.635307582,0.9006636507
+29.47203729,-0.6118070376,-0.2042629771,0.07183129013,0.6489922567
+29.48207829,0.8585012121,0.5205442804,-0.4640449744,1.106041779
+29.49211829,-0.7988387818,0.3275210771,-1.09843162,1.397127582
+29.50215929,0.5682036561,-0.04747231962,0.6036606967,0.8303705515
+29.51220029,-0.2880242134,-0.5047292066,-0.1175454068,0.5928966539
+29.52224029,-0.3537599822,-0.1211547925,0.02046116173,0.374490678
+29.53228129,0.621631237,0.08515423494,0.2300440818,0.668279072
+29.54232229,-0.4932514877,0.2902591654,0.04039315045,0.5737412482
+29.55236229,0.2864559719,-0.325632061,0.1231733519,0.4508491295
+29.56240329,-0.157570475,-0.8568969554,1.507829686,1.741450892
+29.57244429,-0.135863162,-0.3873386414,1.103087173,1.176983999
+29.58248429,0.2336363187,0.4781208671,-0.0753770417,0.5374636652
+29.59252529,0.04178926455,-0.1145528841,-0.2645952791,0.2913406384
+29.60256629,-0.1162191395,-0.7900618918,0.5595978338,0.9751176426
+29.61260629,1.155407474,-0.1376570147,0.1205947298,1.169811512
+29.62264729,-0.006080236332,-0.171275106,-0.4877373075,0.5169717714
+29.63268829,-0.2073093399,0.01590943325,-0.4653021258,0.5096433466
+29.64272829,0.5520258357,-0.0007969115395,-0.2053202999,0.5889733303
+29.65276929,0.2713997936,-0.2694622821,-0.606780771,0.7172521687
+29.66280929,0.0586971921,0.101240784,0.2102237749,0.2406015217
+29.67285029,-0.02154848803,0.1690565262,0.2785876662,0.3265815888
+29.68289129,0.3074390342,-0.1985883457,-1.157413069,1.213903251
+29.69293129,-0.4585544389,-0.2548363493,1.053936063,1.177282873
+29.70297229,-0.121420585,0.06783286356,0.229289791,0.2681754353
+29.71301329,0.09908379184,0.1788064659,-0.2497322416,0.3227313784
+29.72305329,0.05474234557,-0.4627819028,0.6183038789,0.7742502829
+29.73309429,0.05802586779,-0.6611636042,1.15119397,1.328815966
+29.74313529,-0.1134683718,-0.4708785788,0.8519668025,0.9800250711
+29.75317529,0.1585734918,0.3677371665,0.5100461894,0.6484776722
+29.76321629,-0.165374699,0.7557081112,-1.554798616,1.736618057
+29.77325729,0.5035903152,-0.8185038451,-1.09409474,1.456226305
+29.78329729,0.2401926737,-1.203071418,-0.04554279327,1.22765936
+29.79333829,0.792470433,-0.002387217153,0.4445667297,0.908655415
+29.80337929,-0.7535692728,0.7233819987,-0.2302370399,1.069652869
+29.81341929,0.497136122,-0.07875636689,0.6850632942,0.8500932926
+29.82346029,-0.3992697753,-0.6471842272,1.446340367,1.634063718
+29.83350129,0.0428294294,-0.4621330811,-0.2365871161,0.5209364723
+29.84354129,0.120002617,-0.9060479924,0.9571909565,1.323456882
+29.85358229,-0.193736655,-0.5005439524,0.8681209052,1.020642957
+29.86362329,0.1174928641,0.6598185984,-0.8615422028,1.09152193
+29.87366329,-0.05003562933,-0.3729579626,-0.736682514,0.8272256841
+29.88370429,0.5949013119,-1.133980279,0.6236698687,1.42435352
+29.89374529,-0.03656812124,-0.08746575806,-0.1286931235,0.1598418167
+29.90378529,0.4830369502,0.4866167252,-2.823853158,2.90590213
+29.91382629,-0.3260937352,-0.4875256383,-0.9471945566,1.114089718
+29.92386629,-0.9370434979,-0.5386105322,1.625975018,1.952420697
+29.93390729,0.5177563645,0.4424812837,-0.01955075026,0.6813542186
+29.94394829,-0.0933690339,-0.3432261136,-0.3340543538,0.4879695204
+29.95398829,0.5357313998,-0.6258970731,0.8920161366,1.214268532
+29.96402929,-0.09149379529,-0.001608267529,-1.271110423,1.274400019
+29.97407029,-0.2944397601,0.1599251671,-0.3895596331,0.5138361015
+29.98411029,0.5248681867,-0.6897376315,1.196995795,1.477844223
+29.99415129,-0.2600360589,-0.2768679452,0.3891234308,0.5437753722
+30.00419229,-0.04303649392,0.396842596,-1.14532629,1.212892615
+30.01423229,0.5197383148,0.1892068536,0.2035351449,0.5893672069
+30.02427329,-0.41184498,0.08745750801,0.3798848301,0.567078114
+30.03431429,-0.06499412259,0.008122285036,-0.04479961216,0.07935497927
+30.04435429,0.431521153,-0.8765397263,0.00159512043,0.9770030407
+30.05439529,-0.1251191317,-0.6476607022,0.5030763084,0.8295811921
+30.06443629,-0.07411836457,0.4228587223,0.01002563596,0.429422338
+30.07447629,0.0445183885,0.873104414,-1.476708466,1.716088896
+30.08451729,-0.006415857375,-0.8592572571,-0.6764842594,1.093615632
+30.09455829,-0.8662095235,-0.5365041824,1.718401371,1.997763486
+30.10459829,0.6237929526,0.09875225471,-0.5092369348,0.8112902756
+30.11463992,-0.7262436991,0.1471736414,0.05346752465,0.7429325457
+30.12468092,0.5351094753,0.003331432845,1.436415887,1.532854804
+30.13472092,0.2837641331,-0.1415881252,-0.7138988382,0.7811663277
+30.14476192,0.4999240744,0.2959258666,-0.8704679775,1.046523148
+30.15480192,-0.08271030894,0.0853607787,-0.195672394,0.2289435379
+30.16484292,-0.3133144992,-0.3592570227,-1.188873428,1.280879234
+30.17488392,0.4039994418,0.1386384424,0.8792247677,0.9774826642
+30.18492392,-0.0507678195,0.3956756014,0.5294484204,0.6629118968
+30.19496492,-0.03588432591,0.1371983006,0.4532270408,0.474895577
+30.20500592,0.4940698421,-0.5997549029,-0.1808760148,0.7978264756
+30.21504592,-0.3381980198,-0.1543546161,0.3364569747,0.5014045711
+30.22508692,-0.5409141159,0.1371377089,0.4704897755,0.7299009939
+30.23512792,0.112725483,0.2170059969,0.5536050224,0.6052083592
+30.24516792,0.4245451689,-0.377396584,0.6839833134,0.889100644
+30.25520892,-0.4618845744,-0.5067356787,0.277279644,0.7395961122
+30.26524992,0.04674370173,0.2010239668,-0.4922460955,0.5337619577
+30.27528992,0.3400468728,0.447788582,-1.281380473,1.399314977
+30.28533092,-0.2053398515,-0.496033264,-0.3185680032,0.6242587815
+30.29537192,-0.03773824959,-0.7713586224,0.358315621,0.8513567901
+30.30541192,0.2993715394,0.2063574863,-0.6468377066,0.7420281325
+30.31545292,-0.6414279357,1.162538154,-2.098924132,2.483627844
+30.32549392,1.189499373,-0.006457756329,0.2145267409,1.208706822
+30.33553392,0.05792240862,-1.121556919,0.20221192,1.141111121
+30.34557492,-0.369740386,0.424522986,0.5438074279,0.7827223246
+30.35561492,0.02764935407,1.074512196,-1.88454591,2.169528574
+30.36565592,-0.1790027862,-0.3973310213,0.4371290714,0.6172485423
+30.37569692,0.08104386161,-0.1845860732,1.159947837,1.177335598
+30.38573692,0.2017937345,0.4122426637,-0.2650829369,0.5300317806
+30.39577792,0.04373892725,0.4302401011,-0.1707509762,0.464946808
+30.40581892,-0.08389340166,0.01127349573,1.489461243,1.491864602
+30.41585892,-0.04216637341,0.3820729313,0.2645321292,0.4666208046
+30.42589992,-0.07643556132,-0.1119422393,-0.1372247958,0.1928836555
+30.43594092,-0.02492296186,-0.3596457529,0.7503299153,0.832442913
+30.44598092,0.03179461883,0.1934626764,0.1740201545,0.262148277
+30.45602192,-0.5652818755,0.9199020197,-0.9094443476,1.411684223
+30.46606292,0.4044527838,0.4185783777,-0.4805873322,0.7548205724
+30.47610292,-0.4152521525,-0.9698548561,0.2308895892,1.079982775
+30.48614392,0.8935160936,-0.3198832612,0.3471977252,1.010565471
+30.49618492,-0.1459901101,0.555157714,-0.8052750313,0.9889292572
+30.50622492,-0.05064071565,0.8033350714,-1.628454237,1.81652826
+30.51626592,0.5459884028,0.07974479302,-0.3796415859,0.669768842
+30.52630592,-0.06140075276,-0.3572536936,-0.05479952037,0.3666104764
+30.53634692,-0.07945825204,-0.9745851805,0.9273397511,1.347623427
+30.54638792,0.1957325473,-0.1455910925,1.178670622,1.203649629
+30.55642792,-0.3289218141,0.6593046281,-0.5141743237,0.8984694695
+30.56646892,0.4271918014,-0.2886589104,0.5046410233,0.7214425578
+30.57650992,-0.4491869437,-1.051358318,2.094511238,2.386231454
+30.58654992,0.366338878,-0.2842672129,0.7961399263,0.921330996
+30.59659092,-0.5112508986,0.08879453782,-0.6138933241,0.8038202316
+30.60663192,-0.1188000183,0.351544326,0.1719905859,0.4089958669
+30.61667192,0.02904287347,0.7956587736,-0.4525002319,0.9157908234
+30.62671292,-0.2260991847,-0.04563264853,-1.292974917,1.313387725
+30.63675392,0.3944214468,-1.044723482,1.181700064,1.625862993
+30.64679392,0.1098968833,0.1087165863,-0.6254918611,0.6443110191
+30.65683492,-0.2707944971,1.225232658,-1.364965251,1.854091384
+30.66687592,0.6631951462,0.679208404,-1.61705626,1.875106078
+30.67691592,-0.06216449048,-0.6101907941,0.3224382752,0.6929384319
+30.68695692,0.1065156943,-0.1830831195,0.4459285462,0.4936773137
+30.69699692,-0.05649119295,0.8166698659,-0.8305028433,1.166137169
+30.70703792,0.3395100253,0.6938139448,-1.918481396,2.068143059
+30.71707892,-0.1270836682,-0.1434208162,0.02550146163,0.1933135116
+30.72711892,0.4262673566,-0.378977927,0.4791851699,0.7449473509
+30.73715992,-0.09413886552,0.6025754535,-0.1243615061,0.6224348057
+30.74720092,-0.3718459319,0.6396969406,0.1827997488,0.762166203
+30.75724092,0.6069491343,-0.5916932736,0.5544300646,1.012857778
+30.76728192,-0.5566531029,-0.06889284499,0.8048464304,0.9810130874
+30.77732292,0.2531932817,0.5699481729,0.6101300561,0.8724714569
+30.78736292,0.05634475674,-0.7852602314,0.6086489564,0.9951190455
+30.79740392,-0.987074687,-0.4239117693,1.167712939,1.586685582
+30.80744492,0.2231146927,0.763673773,0.2404012549,0.8311260801
+30.81748492,-0.5381422434,-0.06104093886,-0.4087566268,0.6785315396
+30.82752592,0.271755889,-0.8177770362,1.210433866,1.485853522
+30.83756592,-0.2153119489,-0.3677574125,-0.03467457354,0.4275594413
+30.84760692,0.1249610376,0.8714753066,-1.571665494,1.801448555
+30.85764792,0.7424931845,-0.2969665613,0.4070673662,0.897323302
+30.86768792,-0.2419979833,-0.2126543528,0.4781262392,0.5765323914
+30.87772892,0.2899346267,0.5339680988,-1.466511506,1.587400396
+30.88776992,-0.4510580161,0.6008573954,-1.125821148,1.353497765
+30.89780992,0.3672393126,-0.3294627912,0.2972297591,0.5759826154
+30.90785092,0.04266550636,-0.1519521962,-0.8073578095,0.8226399261
+30.91789192,0.1270165075,0.8177029227,-0.3918581736,0.9156003993
+30.92793192,-0.08367233123,0.33399537,0.4534574211,0.5693659622
+30.93797292,0.05330839816,-0.3596052975,1.757086549,1.794299556
+30.94801392,0.2981316921,-0.3873850536,-0.3001194531,0.5736038456
+30.95805392,-1.147039231,0.2109262813,-0.580022158,1.302541592
+30.96809492,1.29374748,-0.7193683237,1.456934937,2.0770009
+30.97813492,-0.2022917711,-1.171084809,0.1640845656,1.199702186
+30.98817592,-0.3630792745,0.5861975121,0.8135821706,1.066475518
+30.99821692,0.1078682649,1.331324319,-0.1296210766,1.341961858
+31.00825692,-0.1601531719,0.1717975547,-1.763355349,1.778928196
+31.01829792,-0.03794026176,-0.7900151141,0.2731304598,0.8367577858
+31.02833892,0.4950403337,-0.9417502141,-0.3391110259,1.116671252
+31.03837892,0.3275561969,-0.1798616325,-1.051080868,1.115533173
+31.04841992,0.3262235434,0.598607131,-0.6980084449,0.9756885193
+31.05846092,-0.2726085044,-0.4075434027,-1.476250629,1.555545866
+31.06850092,-0.5150221334,-1.017517704,0.7511122727,1.365562053
+31.07854192,-0.2255172588,-0.6576098858,-0.4736537039,0.8412232921
+31.08858292,-0.4578173974,0.9771817828,-1.540205135,1.880615023
+31.09862292,0.07391963233,-1.149301592,-0.2172725934,1.171992168
+31.10866383,-0.7313176936,-1.577899357,1.5460313,2.326973298
+31.11870383,-0.7499089888,0.3749017233,-0.1023818225,0.8446282207
+31.12874483,-0.7795945718,1.133964272,-1.970510505,2.403446342
+31.13878583,0.1807852551,-0.2673431415,0.7519735676,0.8183030674
+31.14882583,-0.9118175132,-0.8963150096,-0.80498384,1.510890716
+31.15886683,-0.5118103309,-0.4342766168,0.7448715395,1.002686195
+31.16890783,0.1523301821,-0.4033957899,0.9202809924,1.016292159
+31.17894783,-1.721914524,0.8378215107,0.004878332019,1.914930367
+31.18898883,-0.3084742837,0.8493153825,-0.1756971359,0.9205229418
+31.19902983,-1.19250031,-0.7743963971,0.6560885864,1.565949872
+31.20906983,-0.3773306201,-0.6850827362,0.9232496238,1.210002736
+31.21911083,-0.008598728045,-0.6000837357,0.2228414816,0.6401818131
+31.22915183,-0.6617530035,-0.649090054,0.1003692108,0.9323673709
+31.23919183,-0.3868203953,-0.6942325323,1.007305103,1.283063676
+31.24923283,-0.5247876414,0.4265428336,-0.2201751512,0.7112087982
+31.25927283,-0.1206827578,0.3055022536,-1.648986735,1.681384313
+31.26931383,-1.700590459,-0.5704123322,0.009536808729,1.793730495
+31.27935483,0.5815330786,-0.9699772822,-0.4343013579,1.211467837
+31.28939483,-0.8155098514,-0.6964439493,-0.14435606,1.082094804
+31.29943583,-0.4794321783,-0.4721163978,0.6561827266,0.9398536468
+31.30947683,-1.0729238,-0.2070606505,0.6097698677,1.251342832
+31.31951683,-1.227051215,0.3656762423,0.05876451731,1.281728156
+31.32955783,-0.4693630902,-0.8939168472,-0.1606721306,1.02235247
+31.33959883,-2.470742436,-1.733628105,1.450288991,3.348637447
+31.34963883,-0.5600947009,-1.330961061,1.920627909,2.402909691
+31.35967983,-1.165908927,-0.1624713188,-0.3320312172,1.223104773
+31.36971983,-1.199825263,0.3975928304,-1.381640341,1.872589317
+31.37976083,-0.4819628897,-1.656021958,0.8336042064,1.915618158
+31.38980183,-1.776572249,-0.9075967737,1.358277791,2.413474553
+31.39984183,-0.8019927699,0.2232216419,-0.1612100744,0.8479439796
+31.40988283,-1.536193506,0.08617799104,-1.393306705,2.075721732
+31.41992383,-1.004236484,-1.544166477,1.06727707,2.128854474
+31.42996383,-2.896805944,-0.7018461918,-0.3405307299,3.000005655
+31.44000483,-1.818817359,0.9958914111,-1.880370414,2.799230105
+31.45004583,-1.1050332,-0.32170434,-0.5324053574,1.268088135
+31.46008583,-2.258374779,-1.940767912,1.773104997,3.465651174
+31.47012683,-0.9588030338,-0.608234133,0.004690636396,1.135462029
+31.48016783,-1.437216371,0.6662892003,-2.532988093,2.987567719
+31.49020783,-0.2184442475,0.04132426016,-1.167977818,1.188948177
+31.50024883,-1.93961528,-1.227995248,-0.07689439416,2.296952875
+31.51028883,-2.135568779,-0.207572757,-0.8750276363,2.317199565
+31.52032983,-1.280514939,0.4314543486,-0.8289065534,1.585231036
+31.53037083,-2.106215464,-0.1345623667,1.072748895,2.367496737
+31.54041083,-2.081634061,-0.007970878696,1.405070134,2.51147088
+31.55045183,-1.412292468,0.07356430435,-0.9478921294,1.702492647
+31.56049283,-1.998807229,-0.6568485783,2.224021218,3.061527522
+31.57053283,-1.733542151,-0.6209706478,0.8584244674,2.031665696
+31.58057383,-3.359334735,0.4892947134,0.07419356525,3.395591828
+31.59061483,-1.495819213,0.8124878642,-1.232582535,2.101635399
+31.60065483,-1.950097729,-0.5448023316,-0.1628987503,2.031311581
+31.61069583,-1.822675937,-1.285373244,0.7542668456,2.354410844
+31.62073583,-1.747147452,-0.1312035159,-0.009728012681,1.752093952
+31.63077683,-2.264759062,0.8187350294,-1.73983434,2.97093995
+31.64081783,-1.343122685,-1.151435899,1.277592062,2.182206372
+31.65085783,-3.031647122,-1.993913401,1.512027403,3.931005188
+31.66089883,-2.970942791,-0.1167071902,1.961395866,3.561908951
+31.67093983,-2.167125617,0.577163235,-2.026626234,3.022708178
+31.68097983,-1.861035718,-1.981406646,2.992423707,4.042774528
+31.69102083,-2.306482454,-1.582367945,2.196662681,3.556554028
+31.70106183,-2.603858978,-0.1997565828,-0.734723112,2.71289556
+31.71110183,-2.318347039,0.2288866255,-0.8170975167,2.468758885
+31.72114283,-3.062918909,-0.9989865616,0.459417488,3.254306504
+31.73118283,-3.925393158,-0.9744552261,-0.1665889281,4.047965699
+31.74122383,-3.914823146,0.1884991395,-0.6372266382,3.97082233
+31.75126483,-3.47977773,-0.2410314751,0.6515809679,3.548451349
+31.76130483,-2.865000014,-0.5397582676,1.075933873,3.107603219
+31.77134583,-2.868161896,-0.3227247888,0.4832998556,2.926445404
+31.78138683,-3.101589177,-0.6880983645,-0.5715688384,3.228006462
+31.79142683,-3.091944195,-0.2323907522,-0.0419806695,3.100949329
+31.80146783,-3.020809016,-0.1946569337,-1.455493013,3.358815021
+31.81150883,-3.776559592,-0.02685104011,-1.603822256,4.103092634
+31.82154883,-2.800687366,0.2588111586,-0.0660554105,2.813395859
+31.83158983,-4.020021572,-0.04359363307,0.1734553134,4.023998085
+31.84162983,-2.762664677,-1.100126435,0.2011652684,2.98044657
+31.85167083,-3.23235163,-1.166719424,1.150508677,3.623948329
+31.86171183,-3.253440198,0.238124678,0.307925486,3.2766438
+31.87175183,-3.613243058,0.8065641231,-1.402266394,3.958841008
+31.88179283,-3.320343162,-0.355861837,-0.1249590915,3.341695848
+31.89183383,-3.826387517,-0.8573496761,0.3256326091,3.93475876
+31.90187383,-4.596169073,0.1802377182,-1.456237364,4.824715851
+31.91191483,-3.402938884,0.6106841895,-1.109548931,3.630981556
+31.92195483,-3.310975046,0.1693818507,-1.06702564,3.48278476
+31.93199583,-3.790676233,0.02730690366,-0.9358825332,3.904593203
+31.94203683,-3.621477692,0.1166266539,-0.4395036256,3.649913134
+31.95207683,-3.779570031,0.1524704239,0.2423436999,3.790399361
+31.96211783,-3.590382199,0.3827278195,0.2854675001,3.621990698
+31.97215883,-3.584416285,-0.373489036,-0.04473529279,3.604099806
+31.98219883,-3.027239491,-0.2552086524,-0.08663527071,3.039213066
+31.99223983,-3.460544776,-1.027019429,1.755144104,4.013809896
+32.00228083,-2.614177559,-0.003776017665,1.006108763,2.801105748
+32.01232083,-4.347508333,-0.3609217981,0.6007376736,4.403632478
+32.02236183,-3.178568063,-0.1244517999,-0.3857396472,3.204306206
+32.03240183,-2.281076594,-0.1798937557,-0.7894711769,2.420524102
+32.04244283,-3.965878694,-0.9778720466,-1.612302473,4.391349089
+32.05248383,-3.832690524,-0.6735292228,1.597327754,4.206496668
+32.06252383,-3.177973986,0.2181714932,-1.415299838,3.485712422
+32.07256483,-3.920220711,0.4951101349,-1.635180289,4.276339444
+32.08260583,-3.09124019,-0.4148999309,0.8188078272,3.224647907
+32.09264583,-4.131196145,-0.4280881065,-0.8918360424,4.247989235
+32.10268683,-4.095165602,0.1563190064,-1.003944708,4.219327188
+32.11272642,-3.138633627,0.3797081711,-1.016208073,3.320824926
+32.12276742,-4.209434522,0.2830303258,-0.2607343626,4.226988002
+32.13280842,-3.65515707,0.1163398937,-0.04204791248,3.657249814
+32.14284842,-3.48667072,-0.5223578674,-0.196367628,3.531046686
+32.15288942,-3.992577081,-0.7802691212,0.7888940567,4.143892552
+32.16293042,-3.659296898,0.08368664777,1.877741506,4.113802427
+32.17297042,-3.629722559,0.9032299999,0.2452526897,3.748447568
+32.18301142,-3.598648116,-0.5182260056,1.87403554,4.090334419
+32.19305242,-4.208970838,-0.8234033002,2.333447766,4.882459112
+32.20309242,-3.544531842,0.2500362238,0.550518862,3.595732903
+32.21313342,-3.125061362,0.3668089576,-1.173266625,3.358141138
+32.22317342,-3.681546431,-1.05149697,0.8830342287,3.929272127
+32.23321442,-3.821084678,-0.7025484424,0.3055567789,3.897130659
+32.24325542,-4.020394332,0.4166061484,-0.9788934821,4.158769496
+32.25329542,-3.632716333,0.08674499737,-1.284228067,3.854010168
+32.26333642,-2.55234647,-0.5977927966,1.093429912,2.84032
+32.27337742,-3.634274908,-0.4452237009,-1.72386267,4.046959446
+32.28341742,-4.441141259,-0.3862486107,-0.8186932218,4.532458744
+32.29345842,-3.336348453,-0.3179950126,-0.3320452505,3.367877058
+32.30349942,-4.264988333,-0.5944021058,-0.06302362919,4.306670561
+32.31353942,-3.42549101,0.1017728806,0.1663158631,3.4310359
+32.32358042,-2.659185917,-0.3652682893,-0.9368865001,2.84296447
+32.33362042,-3.469588079,-0.2685583026,-0.6137032896,3.533666188
+32.34366142,-3.491008769,-0.4174146722,-0.5907915598,3.565166462
+32.35370242,-3.746224822,-0.5407810918,-1.235799088,3.981688586
+32.36374242,-3.558117848,-0.1299270047,-0.5600989401,3.604274472
+32.37378342,-2.565118251,-0.5475695995,-0.8060345846,2.743967175
+32.38382442,-3.154822521,-0.4972361825,-1.074750397,3.36975331
+32.39386442,-3.406744545,-0.4862546364,-0.7942425048,3.531737974
+32.40390542,-3.628483826,-0.3481253494,-0.1802310669,3.649598522
+32.41394542,-4.422168799,-0.5586155381,0.5930602795,4.49659301
+32.42398642,-3.988339311,-0.4763937092,0.8223939246,4.100016243
+32.43402742,-4.016693045,-0.9940609402,1.74913609,4.492377681
+32.44406742,-3.436058683,-0.912595266,1.535988708,3.872801402
+32.45410842,-3.822568116,-0.304229735,-0.02120785117,3.834714136
+32.46414942,-3.343609526,-0.5511753581,-0.413220976,3.413835162
+32.47418942,-3.489240279,-1.047821703,0.2727965838,3.653374607
+32.48423042,-4.304350035,-0.5167408494,-0.0207558614,4.335306348
+32.49427042,-3.649038543,0.1519953925,-1.006612208,3.78838396
+32.50431142,-3.154673124,-0.4007478417,-0.824457407,3.285162305
+32.51435242,-3.229084791,-0.7693782435,-0.1115175122,3.321350271
+32.52439242,-3.033979284,-0.4768730712,-0.5348687893,3.117454546
+32.53443342,-2.918038646,-0.08194486273,-1.333184465,3.209212569
+32.54447442,-3.111383556,-0.9622603463,-0.6979300922,3.330729502
+32.55451442,-3.233449445,-0.9511312676,-0.2966491306,3.38346667
+32.56455542,-3.225282054,-0.6588846519,0.3413060707,3.309541229
+32.57459542,-2.717979963,-0.4689828019,0.4568605006,2.79572557
+32.58463642,-2.291008382,-0.9533268971,-0.2005811316,2.489534971
+32.59467742,-3.185555486,-1.062945453,0.5128282946,3.397147281
+32.60471742,-3.033505952,-0.9271029389,-0.3573175013,3.192076756
+32.61475842,-3.446405331,-0.5753812595,-1.064611325,3.652693605
+32.62479942,-3.285595791,-0.5428613484,0.4809200388,3.364687538
+32.63483942,-2.780628493,-0.4065603396,-0.7445926273,2.907164307
+32.64488042,-2.648288461,-0.7976735048,-1.02257803,2.948793079
+32.65492142,-2.492679435,-0.8358558961,-0.9865141582,2.808080488
+32.66496142,-1.923015473,-0.4898423052,-1.465991689,2.46719793
+32.67500242,-2.493273512,-0.6706912766,-2.064483447,3.305802701
+32.68504242,-2.691680941,-0.03501566721,-0.600426017,2.758057974
+32.69508342,-1.944955688,-0.7317712183,0.07836613834,2.079539131
+32.70512442,-2.992098017,-0.8246046837,0.4838296133,3.141132682
+32.71516442,-1.954036122,-0.7349621169,0.5360353088,2.155402591
+32.72520542,-2.069563069,-0.9739949041,1.10752521,2.541332222
+32.73524542,-2.228586431,-1.674240421,1.865074098,3.353830624
+32.74528642,-1.844087856,-1.614501319,2.332392343,3.3833901
+32.75532742,-2.483272142,-0.6880884243,1.634839981,3.051689364
+32.76536742,-2.079900947,-1.355588948,0.6395520759,2.563715312
+32.77540842,-2.622886987,-2.20376544,1.996323624,3.965025381
+32.78544942,-2.201570395,-1.706792309,1.579582039,3.202363441
+32.79548942,-1.908197605,-1.54387514,-0.2346464252,2.46573062
+32.80553042,-1.653431057,-1.37641483,0.3254823357,2.175842549
+32.81557142,-1.895904711,-1.278165235,-0.5638259554,2.35500759
+32.82561142,-1.834705998,-1.673434674,-1.393411955,2.847477232
+32.83565242,-1.527672505,-2.301968842,-0.8067841977,2.878149505
+32.84569242,-1.83379851,-2.237586612,-1.574087411,3.293533361
+32.85573342,-0.6546109951,-0.8923087167,-2.993140576,3.191178608
+32.86577442,-1.151870493,-1.275974283,-0.3105736899,1.746817684
+32.87581442,-1.291431106,-2.950486015,0.04794190586,3.221096157
+32.88585542,-1.328504061,-1.653798116,-0.504534604,2.180487655
+32.89589642,-0.7834000129,-1.600795445,-1.070778968,2.079141466
+32.90593642,-1.333147042,-2.041359463,-0.5736305666,2.504691902
+32.91597742,-1.06626996,-2.778281128,-0.5798783165,3.031837152
+32.92601742,-1.764407556,-2.551894188,0.2165159637,3.1100124
+32.93605842,-1.544594201,-1.404617705,-0.2712663674,2.10530463
+32.94609942,-0.7641452779,-2.235022608,-1.25676428,2.675574801
+32.95613942,-1.749132728,-2.551284323,0.2732713777,3.105349295
+32.96618042,-0.9350897969,-2.601597275,-0.07676575541,2.765609208
+32.97622142,-0.9315641452,-2.604573215,-1.224934376,3.025240092
+32.98626142,-1.901174661,-2.546796293,-0.296759643,3.191974739
+32.99630242,-1.605231143,-2.64148084,-0.4771614486,3.127598296
+33.00634242,-1.592922315,-2.542397725,-0.2500971079,3.010603969
+33.01638342,-2.086514879,-2.966061828,0.0699543339,3.627114654
+33.02642442,-0.9953837997,-2.742047395,-0.08046821237,2.918233705
+33.03646442,-0.6834486587,-3.028022141,-0.3398378348,3.122740769
+33.04650542,-1.900749422,-3.550646568,-0.2125199765,4.033001879
+33.05654642,-0.891271713,-3.112721106,0.06796394169,3.238520812
+33.06658642,-1.330733166,-2.87666521,-0.09734853923,3.171045604
+33.07662742,-2.410620634,-3.104180663,0.2193512785,3.936387228
+33.08666742,-0.4296653198,-3.196416397,0.7143783098,3.303335653
+33.09670842,-0.8013308651,-3.188289352,-0.1276102191,3.289924697
+33.10674942,-1.903098102,-3.532239826,0.06352999806,4.01279661
+33.11679208,-1.282178618,-3.910421362,0.9070580989,4.214039823
+33.12683308,-1.298149849,-2.477059183,0.04081356525,2.796905607
+33.13687408,-1.594032556,-2.513645796,-0.7292056793,3.0644895
+33.14691408,-1.299573938,-3.376849193,0.1087851083,3.619922249
+33.15695508,-1.582280822,-3.167833745,0.439351598,3.568166624
+33.16699508,-1.512164374,-2.937693476,-1.559424933,3.653558563
+33.17703608,-1.963787962,-2.793935294,-0.1931703705,3.420504696
+33.18707708,-1.14910074,-3.015038399,-0.174682644,3.231315998
+33.19711708,-0.8377468856,-2.559456099,-0.6791728091,2.777392855
+33.20715808,-3.603934583,-4.113214495,1.275405788,5.615473078
+33.21719808,-1.196839455,-4.01524352,0.9650665712,4.299530055
+33.22723908,-2.049712211,-2.12070004,-2.838388166,4.093303823
+33.23728008,-2.019111977,-3.230065953,1.535261314,4.106965612
+33.24732008,0.2933157608,-3.278197309,-0.7723902905,3.380709762
+33.25736108,-0.8785673214,-2.90574429,-0.06221262038,3.036297223
+33.26740208,-2.345843132,-3.997338468,0.3578425813,4.648628415
+33.27744208,-1.299749062,-3.376764993,-1.865961705,4.071081248
+33.28748308,-0.6519339935,-4.2042726,0.05464749277,4.254869255
+33.29752308,-1.860132762,-3.804489987,-0.8104451394,4.311735066
+33.30756408,-0.2955893227,-3.563732345,-0.9229373825,3.693152405
+33.31760508,-0.315315124,-3.918501045,0.02446650445,3.931243146
+33.32764508,-1.91277042,-3.736450032,-0.7979385298,4.272757355
+33.33768608,-0.619373627,-3.278898975,0.07113897979,3.33764332
+33.34772708,-0.6017747504,-4.219224807,-0.107265417,4.263273003
+33.35776708,-0.6689490256,-3.964511323,0.1697271287,4.024133463
+33.36780808,-0.9686339575,-4.12461218,-0.428973375,4.258485122
+33.37784808,-1.498678209,-4.148573485,-0.9720598412,4.516812889
+33.38788908,-1.002834614,-3.954367281,0.5349372017,4.114469062
+33.39793008,-1.449857613,-4.336805005,0.338781243,4.585273981
+33.40797008,-0.9799562135,-4.287898893,0.554009065,4.433206192
+33.41801108,-1.331792389,-3.387168651,0.06404396832,3.640148907
+33.42805208,-1.761820017,-3.912459701,0.13420237,4.292943158
+33.43809208,-0.989748107,-4.636628881,-0.4331243134,4.760832424
+33.44813308,-1.257002115,-4.666465469,-0.7645620382,4.892903984
+33.45817308,-1.720902517,-4.661997027,0.2550321579,4.976018805
+33.46821408,-1.118900822,-3.833021476,-0.8339848602,4.079157196
+33.47825508,-1.650858867,-4.323772438,-0.947659995,4.724235659
+33.48829508,-0.7348472922,-4.505006595,0.01035132587,4.564558261
+33.49833608,-0.8867338351,-4.669264531,-0.6714655942,4.799916061
+33.50837708,-1.760254571,-4.876725496,-0.775505687,5.242361757
+33.51841708,-1.247202035,-4.460683531,0.1845211691,4.635435098
+33.52845808,-1.37626675,-4.041570316,-0.8268974501,4.348811352
+33.53849808,-2.012932347,-4.604916507,-0.3479777437,5.037682124
+33.54853908,-1.257492112,-4.679921374,0.6643232203,4.891244813
+33.55858008,-1.365040973,-4.40157432,0.2960965687,4.617885505
+33.56862008,-2.02042994,-4.357393636,-0.8020789433,4.869532531
+33.57866108,-1.800155386,-4.310154273,0.06063387215,4.671366581
+33.58870108,-2.289086695,-4.691173756,0.9982635534,5.314466974
+33.59874208,-3.271811565,-5.308996409,-0.6940487105,6.274702973
+33.60878308,-2.488298408,-5.532833671,2.257913434,6.473179317
+33.61882308,-0.1534767297,-4.331864985,0.1034366602,4.335816935
+33.62886408,-0.3660568229,-1.696735682,-2.000134254,2.648291262
+33.63890508,-3.472602904,-4.450303262,0.7602964944,5.695807301
+33.64894508,-3.596663571,-7.376709273,3.632586232,8.974826532
+33.65898608,-0.5804442174,-5.715733992,-0.9327501798,5.820356815
+33.66902608,-2.627346366,-2.938222357,-1.712693319,4.297606072
+33.67906708,-1.339917387,-3.995526416,1.253733668,4.396755401
+33.68910808,-1.803176204,-5.647425064,-0.4749161178,5.947301876
+33.69914808,-2.392043737,-4.846987435,0.1008440048,5.406045685
+33.70918908,-2.111078447,-4.644446901,-0.7482874829,5.156304237
+33.71923008,-1.989515857,-4.529757859,-0.6834038544,4.994388895
+33.72927008,-1.356984094,-4.845147901,-0.6195879275,5.06959103
+33.73931108,-1.510052652,-4.415931866,-0.2784672135,4.675281515
+33.74935108,-1.695522093,-4.037762024,-1.842888592,4.751268851
+33.75939208,-2.708513905,-5.166236638,-1.473343393,6.016376761
+33.76943308,-2.157433418,-5.513029152,-0.03533881724,5.920241398
+33.77947308,-2.129449814,-4.318831541,0.2073691642,4.81973696
+33.78951408,-1.489940861,-4.20505905,-1.863486578,4.834772757
+33.79955408,-1.758822588,-4.36404689,-0.1748966521,4.708391551
+33.80959508,-2.526747652,-4.979042122,-0.6126414353,5.616995966
+33.81963608,-2.421675087,-5.387912185,0.2481903309,5.912335104
+33.82967608,-2.27638318,-4.549101326,0.3516667521,5.099010959
+33.83971708,-1.960670226,-4.395118117,-0.1586986953,4.815233772
+33.84975808,-2.58184041,-4.778087061,0.5498470169,5.458786276
+33.85979808,-1.923368353,-5.109425676,0.9081661463,5.534468566
+33.86983908,-2.516633138,-5.190852832,0.07149507523,5.769185993
+33.87987908,-2.799197788,-4.47722852,0.2089777333,5.284387871
+33.88992008,-1.440981247,-4.30114196,-0.2435189903,4.542636967
+33.89996108,-2.817597222,-4.666672168,-1.316959611,5.608124984
+33.91000108,-2.848538056,-5.155028111,0.3162823266,5.898179243
+33.92004208,-2.656591507,-4.415412341,-0.6117871571,5.189183761
+33.93008208,-2.3592641,-3.394784065,-1.313655934,4.337784902
+33.94012308,-2.097385583,-3.610057495,-1.453168745,4.420773779
+33.95016408,-2.995886721,-4.915083523,-1.044269446,5.850118115
+33.96020408,-1.779397478,-4.451159879,1.204550398,4.942673498
+33.97024508,-1.879294818,-3.549040046,-1.914475468,4.448893186
+33.98028608,-2.89898257,-3.958015066,-1.477501933,5.123767673
+33.99032608,-1.56521543,-4.443608492,-0.7439868557,4.769598748
+34.00036708,-1.883677745,-4.057758332,-1.59371242,4.749059255
+34.01040708,-4.226938454,-6.738447093,0.3483537197,7.962099486
+34.02044808,-1.532189333,-6.062913006,1.384855725,6.405024875
+34.03048908,-2.760833329,-3.910589762,-3.933452375,6.195721148
+34.04052908,-2.927040142,-5.082391659,0.6145897275,5.89711705
+34.05057008,-1.597656952,-6.000811483,-1.575014779,6.406474673
+34.06061008,-2.550104647,-6.758981345,2.562344039,7.665015949
+34.07065108,-2.503712254,-5.236706697,-0.839510479,5.86484867
+34.08069208,-3.15603611,-5.078649441,-0.01191896439,5.979413528
+34.09073208,-2.359314532,-6.225076761,0.0853061986,6.657719046
+34.10077308,-2.985462012,-5.596772974,1.728406541,6.574514455
+34.11081179,-2.014279692,-5.582297022,-0.7122733122,5.977181275
+34.12085179,-3.348850385,-5.380406114,-0.7707928312,6.384175001
+34.13089279,-2.227431314,-5.687123566,0.260237934,6.113309128
+34.14093279,-3.048131593,-5.49483554,-1.356853994,6.42848167
+34.15097379,-3.199983198,-4.922036448,-0.2562431163,5.876393094
+34.16101479,-2.423801281,-5.202580592,-1.161130729,5.855756316
+34.17105479,-3.461190308,-5.841940295,-0.1154357314,6.791276033
+34.18109579,-2.846499716,-5.20065218,-0.07865089774,5.929209871
+34.19113579,-3.0058571,-4.661696772,-0.3790217811,5.559698842
+34.20117679,-3.560734769,-5.688916322,0.1836756617,6.713891403
+34.21121779,-2.789448433,-5.331601744,0.7844718075,6.068145989
+34.22125779,-2.796161037,-4.824235334,-0.3002814209,5.584078441
+34.23129879,-3.891912878,-5.080369692,-0.4812925065,6.417848902
+34.24133979,-2.331298914,-4.93641709,-0.7246536219,5.507112781
+34.25137979,-2.533164386,-4.982439939,-0.8077355397,5.647483179
+34.26142079,-3.387496972,-4.573313476,-1.852129532,5.985040993
+34.27146079,-2.184833763,-5.242780784,-1.922501941,5.996354112
+34.28150179,-3.158087606,-5.79232667,0.0541984266,6.59753765
+34.29154279,-2.810227099,-4.725999187,-2.819570657,6.179192775
+34.30158279,-2.226351918,-2.781738879,-3.154797962,4.7589352
+34.31162379,-2.746479292,-3.359297021,-0.3135195172,4.350438996
+34.32166379,-3.236034791,-6.128569636,-0.03271517158,6.930538019
+34.33170479,-2.571076856,-4.132259461,-1.390509397,5.061572961
+34.34174579,-2.850280526,-4.720919711,-1.699214317,5.770486227
+34.35178579,-4.029965055,-5.134272834,1.328345894,6.660771629
+34.36182679,-1.928777027,-5.888199372,-0.2667950016,6.201794275
+34.37186679,-3.19905086,-4.916973343,-0.1547044623,5.868090553
+34.38190779,-2.434175411,-4.123257088,0.679721278,4.836163765
+34.39194879,-2.507808228,-4.912986712,-1.483982987,5.71215774
+34.40198879,-4.054709594,-5.322729764,-0.1012597418,6.691963506
+34.41202979,-1.890558456,-5.105883433,0.4665201008,5.464604094
+34.42207079,-2.795811958,-5.047344033,-0.4385821044,5.786587989
+34.43211079,-2.749752563,-4.408112969,0.02862913728,5.195519102
+34.44215179,-2.911339783,-4.73921214,-0.2165118706,5.566229283
+34.45219179,-2.756112872,-5.276479458,1.037393705,6.042646716
+34.46223279,-2.656485381,-4.807408217,-0.2399861026,5.497788798
+34.47227379,-2.748607386,-4.887016304,1.407917728,5.781003654
+34.48231379,-2.891492871,-4.869800346,-0.8677729958,5.729634928
+34.49235479,-2.769833071,-4.22210193,1.044223253,5.156405933
+34.50239479,-2.256908298,-4.194698954,-1.069678522,4.881940855
+34.51243579,-3.167348718,-4.432608418,-0.8202357173,5.509346778
+34.52247679,-1.773057488,-4.627011089,0.6274822533,4.994667001
+34.53251679,-2.790348027,-3.866644428,-1.4489798,4.983625558
+34.54255779,-2.128239148,-3.801560825,-1.948968194,4.772812964
+34.55259879,-2.225383181,-3.943891117,-0.2640783852,4.536115611
+34.56263879,-2.31957817,-4.364807028,-1.615499146,5.200175071
+34.57267979,-2.497942514,-4.414887261,-0.6622591531,5.115616631
+34.58271979,-1.515527107,-4.405937513,-1.157503701,4.800929347
+34.59276079,-3.132836405,-4.711586385,-1.5343357,5.862413858
+34.60280179,-1.610086671,-4.760601255,0.009090666175,5.02551351
+34.61284179,-2.856821221,-5.29574194,0.1896339744,6.020155416
+34.62288279,-2.325898572,-4.590214561,0.1664398241,5.148550873
+34.63292279,-2.123108801,-4.860065025,0.1446916902,5.305540379
+34.64296379,-2.742910736,-5.366577449,1.150099956,6.135669706
+34.65300479,-1.897223112,-5.002834443,0.8662129587,5.420159858
+34.66304479,-2.78149125,-4.600613541,-0.09070961058,5.376854728
+34.67308579,-2.960572754,-4.514125328,0.5591861898,5.427246789
+34.68312579,-2.488470609,-4.800993236,1.232131714,5.546185228
+34.69316679,-2.337112947,-5.069555851,1.014225283,5.673724207
+34.70320779,-2.445193904,-4.105188315,-0.00581271708,4.778240065
+34.71324779,-1.981183867,-4.184421887,-0.3756953001,4.644956728
+34.72328879,-2.420245004,-4.448531555,-0.787807644,5.12519851
+34.73332979,-2.397097486,-4.419149589,-0.8621684396,5.100813059
+34.74336979,-1.693495594,-4.371160905,-1.062844881,4.806725936
+34.75341079,-2.273523453,-4.236310079,-1.794825649,5.131922748
+34.76345079,-1.33608863,-3.945302342,-1.623120992,4.470465876
+34.77349179,-1.977633145,-4.271241053,-2.073621476,5.143387893
+34.78353279,-1.983134059,-4.370218334,-2.1286964,5.250045462
+34.79357279,-1.44754767,-4.222302782,-1.508899727,4.71168902
+34.80361379,-1.7577448,-4.159576191,-2.828719795,5.328545444
+34.81365379,-2.018364118,-4.300283881,-1.189139476,4.896967211
+34.82369479,-0.6335457429,-4.253123748,-1.730108666,4.635053162
+34.83373579,-2.948738282,-4.572985447,-1.461167151,5.634027228
+34.84377579,-1.017771765,-3.802600459,-1.10913144,4.089719082
+34.85381679,-1.515674896,-3.936295584,-1.480678141,4.470358047
+34.86385679,-2.021745271,-4.19604089,-1.584565621,4.919863951
+34.87389779,-1.070059614,-4.256370414,-1.198525427,4.549525237
+34.88393879,-1.963022415,-4.493759768,-1.185214825,5.045004265
+34.89397879,-1.840061755,-3.853048774,-0.004824537635,4.269875337
+34.90401979,-1.688532624,-3.152917498,-1.070666116,3.733410921
+34.91405979,-2.435241504,-4.08903392,0.429867999,4.778638517
+34.92410079,-1.478647987,-4.462850509,0.7897728932,4.767302776
+34.93414179,-1.689237067,-4.681622621,1.495555211,5.196902695
+34.94418179,-2.322020552,-4.436144814,0.4078789598,5.023696398
+34.95422279,-1.879130219,-4.522340081,1.507592289,5.12401451
+34.96426279,-2.404368206,-4.391204868,1.412599593,5.201836625
+34.97430379,-1.53449489,-4.144190705,0.9777205306,4.526027906
+34.98434479,-1.838176906,-4.53984723,0.6661434585,4.942960076
+34.99438479,-1.421244117,-4.642526675,1.633214455,5.122536308
+35.00442579,-1.383361176,-4.357869599,-0.2763201159,4.580509622
+35.01446679,-2.067730552,-3.986300679,-0.1604247934,4.493533004
+35.02450679,-1.361647249,-3.938211424,-0.1172892988,4.168614785
+35.03454779,-1.949386854,-3.675548649,-0.3811273634,4.17792114
+35.04458779,-0.8011631962,-3.637954561,-0.5382426327,3.763812029
+35.05462879,-1.309450762,-3.818005241,-1.090084135,4.180921997
+35.06466979,-1.198523819,-4.257870517,-0.452044149,4.44637657
+35.07470979,-1.317877039,-3.45605119,-0.3044674426,3.71130572
+35.08475079,-1.441691538,-3.608526402,-1.564252979,4.188893012
+35.09479079,-2.045366122,-4.138134744,-0.7270924956,4.672937537
+35.10483179,-0.6915308994,-4.14336537,0.4857475001,4.228669083
+35.11487242,-1.341553,-3.573987191,-0.2680638474,3.826879554
+35.12491242,-1.388676588,-3.778288614,-0.2802149463,4.035146581
+35.13495342,-1.338311742,-4.46681843,0.3838778937,4.678772001
+35.14499342,-1.379107912,-3.837788711,0.5761477929,4.118556434
+35.15503442,-1.726734969,-3.487223574,-1.151310915,4.058060957
+35.16507542,-1.656549523,-4.172659628,0.4585444987,4.512815945
+35.17511542,-1.03898254,-4.42225563,1.086932486,4.670894112
+35.18515642,-1.366270788,-3.444096266,-0.5695258212,3.748713728
+35.19519642,-1.257715183,-3.551785606,-0.554466902,3.808472399
+35.20523742,-1.611720821,-4.512093713,0.1178868842,4.792758183
+35.21527842,-0.7823925376,-3.942590404,0.4226344085,4.04163049
+35.22531842,-1.822742595,-3.344435445,-1.643588585,4.148375881
+35.23535942,-1.539375853,-3.560615194,-0.6000202203,3.925262137
+35.24539942,-0.4109250668,-3.762329808,0.06402876556,3.785245656
+35.25544042,-1.293035728,-3.960025046,-1.100070595,4.308583883
+35.26548142,-1.275528872,-3.641084868,-1.245273916,4.054032566
+35.27552142,-0.371925052,-4.057533507,-0.2021844381,4.079556955
+35.28556242,-1.378646712,-4.058377553,-1.295610257,4.477689254
+35.29560242,-1.307319598,-3.561353697,-0.6502542347,3.849046019
+35.30564342,-0.9037285481,-3.701943858,-0.709327485,3.876113917
+35.31568442,-1.339559538,-3.993051875,-0.1692154974,4.215153249
+35.32572442,-0.6829275987,-4.050227119,-0.1492946184,4.110111763
+35.33576542,-1.241361836,-3.744602804,0.1037068015,3.946363449
+35.34580642,-1.199926493,-3.655646774,-0.2767960793,3.85748532
+35.35584642,-1.542063234,-3.993629287,0.6454583484,4.329393766
+35.36588742,-0.9204502693,-4.493565933,0.5223042923,4.616510074
+35.37592742,-1.516160361,-4.158923057,0.4440895969,4.448887367
+35.38596842,-0.9341791662,-3.817090737,0.09213808537,3.93082203
+35.39600942,-1.221030191,-3.922637657,0.2440885091,4.115529142
+35.40604942,-1.032684358,-4.323009669,-0.6888967288,4.497713673
+35.41609042,-1.173559936,-4.076337276,0.4847213137,4.269510892
+35.42613042,-0.7487046086,-3.934047329,-0.03602820396,4.004820222
+35.43617142,-1.037206156,-3.988170034,-0.1010901725,4.122076668
+35.44621242,-0.4102025702,-4.119942302,0.7005566615,4.199163054
+35.45625242,-1.084802126,-4.027913559,-0.2854043502,4.181188699
+35.46629342,-0.347096276,-3.96067818,0.468094756,4.003318645
+35.47633342,-0.4871198781,-4.070776573,0.356515848,4.115289933
+35.48637442,-0.2613543136,-4.043633506,0.1250023609,4.05399847
+35.49641542,-0.7631151447,-3.916731677,-0.2954481125,4.001302456
+35.50645542,-0.08219512356,-3.558002073,-0.4774491316,3.590834508
+35.51649642,-0.6990264452,-3.466518291,0.2916292959,3.548300252
+35.52653642,0.03271249465,-4.010794958,-0.8750469321,4.105271421
+35.53657742,-0.543954595,-4.348653511,-0.6362460601,4.428485408
+35.54661842,-0.5048131507,-4.099972891,-0.9731526858,4.244012273
+35.55665842,-0.6904671447,-3.890801615,-1.156316716,4.117298924
+35.56669942,-0.4770485973,-3.899130973,-0.9272409332,4.036158255
+35.57673942,-0.2566096088,-4.230690028,-0.3984544176,4.257153101
+35.58678042,0.05499932156,-4.032117707,-0.864767527,4.124175191
+35.59682142,-0.03302043278,-4.235532399,-1.74281525,4.580199783
+35.60686142,-0.7817055628,-4.089159927,-1.324231208,4.368739039
+35.61690242,-0.1437484338,-4.648223618,-0.8877915233,4.734429237
+35.62694242,-0.3213694407,-4.984051432,-0.1474656093,4.996578139
+35.63698342,-0.5381661804,-4.617228112,0.9271374375,4.740042416
+35.64702442,0.1826341629,-4.303196964,-0.7871053934,4.378400878
+35.65706442,-0.8897797228,-4.875823856,1.423880042,5.156820784
+35.66710542,0.1921624749,-4.985779869,1.001832109,5.08906621
+35.67714542,-1.030736212,-4.660230875,1.619149563,5.040021255
+35.68718642,-0.6226869518,-4.046258613,-0.01491975546,4.09391871
+35.69722742,-0.2544752289,-3.66482164,1.348802378,3.913431122
+35.70726742,-0.3226171635,-4.347012489,-0.9878186721,4.469494954
+35.71730842,-1.136637839,-4.382531986,0.2620768833,4.535109312
+35.72734842,-0.2177654771,-3.746845504,-0.2187215334,3.759536161
+35.73738942,-0.5336978478,-3.776533864,-0.9210803068,3.923701104
+35.74743042,0.008987640976,-4.007848546,-0.8583420217,4.098741487
+35.75747042,-0.5239033962,-4.369306753,0.03536688387,4.400746197
+35.76751142,-0.1262624268,-4.301286971,-1.448410281,4.540363878
+35.77755142,-0.3561057755,-3.84246356,-0.6396994257,3.911592117
+35.78759242,-0.03577622551,-3.866516958,-0.7558800924,3.939871577
+35.79763342,-0.1443027681,-3.692188363,-0.2349838096,3.702471552
+35.80767342,-0.3467508883,-4.003315785,-0.1667374474,4.021762652
+35.81771442,-0.4111329718,-3.88821276,0.1917383873,3.91458713
+35.82775442,-0.3401921396,-3.826572289,0.2171398616,3.847796239
+35.83779542,0.01684844584,-3.920343795,-0.09786192477,3.921601241
+35.84783642,-0.7129143863,-4.060494829,1.513595626,4.391678142
+35.85787642,0.03464309908,-4.156459333,-0.1143633521,4.15817668
+35.86791742,-0.3649177853,-3.684628206,0.6246808523,3.754980183
+35.87795742,-0.0488038631,-3.865501005,-0.5177019489,3.900319877
+35.88799842,-0.4313504509,-4.047036878,0.534798038,4.104945754
+35.89803942,0.2508926947,-3.928241629,-0.06182085693,3.936731037
+35.90807942,-0.5547349603,-3.726209803,-0.8779068053,3.868215445
+35.91812042,-0.1620947582,-3.100762965,0.7514958501,3.19464422
+35.92816042,0.2266198792,-3.267200743,-0.901925413,3.39697317
+35.93820142,-0.465359794,-3.747578745,-0.00677282989,3.776367575
+35.94824242,0.3508019124,-3.948395227,0.1988158572,3.968931165
+35.95828242,-0.3466072295,-3.321779823,-0.474279356,3.373321608
+35.96832342,-0.5375569371,-2.741821108,-1.093956746,3.000548585
+35.97836342,0.03612159953,-2.794492534,0.3340853441,2.814623653
+35.98840442,0.3172343264,-3.280113734,-0.2315637732,3.303544385
+35.99844542,-0.1044360955,-3.285132399,-0.2957398885,3.300070281
+36.00848542,-0.5846633489,-2.842501683,-0.5393693912,2.951705674
+36.01852642,-0.2871787243,-2.315042193,0.03666262686,2.333074393
+36.02856642,-0.5889612351,-2.732021466,-0.5253951305,2.84373991
+36.03860742,-0.2861635563,-2.900295855,0.9635971659,3.069548032
+36.04864842,-0.0150457995,-2.778255693,0.6602231526,2.855665541
+36.05868842,-0.1397427348,-2.903631691,-0.7391950625,2.999502354
+36.06872942,-0.1966993478,-2.936680739,0.8882324034,3.074368422
+36.07876942,0.2318672071,-2.893998403,-0.1257426184,2.905993869
+36.08881042,0.0007507459447,-2.686995567,0.2189665318,2.695902833
+36.09885142,0.3052024376,-2.922495101,0.2632743931,2.950159241
+36.10889142,0.07840162363,-3.157104397,-0.2545252043,3.16831786
+36.11893233,0.1087121917,-2.650159863,-0.1855368304,2.658869977
+36.12897233,0.307064118,-2.541444921,-0.4811901802,2.604759998
+36.13901333,-0.05199366085,-2.547547952,-0.06358554661,2.548871717
+36.14905433,0.3645938496,-2.665193346,-0.3047264743,2.707220433
+36.15909433,-0.2343452388,-2.457501416,-0.2988716573,2.486675525
+36.16913533,0.037135123,-2.256353397,-1.004334717,2.470060302
+36.17917533,0.2968761122,-1.928134272,0.1393104976,1.955823257
+36.18921633,0.01144406998,-1.972728793,-0.5297688478,2.042656332
+36.19925733,0.1303476205,-1.984043009,0.1669216347,1.99531451
+36.20929733,0.124796813,-2.375446269,-0.05262611032,2.379304253
+36.21933833,0.1609118116,-2.339199379,-0.04031655192,2.345073937
+36.22937833,0.2226762429,-2.160766624,0.4059382689,2.209815148
+36.23941933,0.5642964004,-2.086589723,-0.1162818235,2.164672853
+36.24946033,0.05404730349,-1.975127759,0.03495991766,1.976176352
+36.25950033,0.3077398734,-1.771164013,-0.370926311,1.83556861
+36.26954133,-0.07665436596,-1.883910026,-0.5153197932,1.954622052
+36.27958133,0.2350446572,-2.399122084,0.3979924875,2.44324186
+36.28962233,0.6936353854,-2.023919119,-0.138721683,2.143973497
+36.29966333,-0.1679121896,-2.138244318,0.1550377536,2.150423208
+36.30970333,1.118064377,-1.699301733,-0.727761417,2.16040066
+36.31974433,0.02625758427,-2.237115034,0.1506722224,2.242337007
+36.32978433,0.2837031759,-2.724503117,-0.4276483959,2.772415531
+36.33982533,0.7205985779,-1.376757623,0.1689377546,1.563094312
+36.34986633,0.01130779787,-1.658226066,-1.265756128,2.086140007
+36.35990633,0.7017026427,-1.795997869,-0.01666514933,1.928282311
+36.36994733,0.282977646,-1.859171041,-0.08123829067,1.882337103
+36.37998733,0.3165058364,-2.002739335,-0.1646815664,2.034271566
+36.39002833,0.3586295434,-1.75123334,0.6845937628,1.914184417
+36.40006933,0.5958365009,-1.754125666,-0.2177918261,1.865318007
+36.41010933,0.05979637728,-2.113152162,0.1562188911,2.119762253
+36.42015033,0.525384971,-1.812969266,0.2833993399,1.9087174
+36.43019033,0.6391679138,-1.463536882,0.1158403587,1.601216667
+36.44023133,0.2066656894,-1.473198967,-0.2316380328,1.505550425
+36.45027233,0.7706285244,-1.625039171,0.3790527713,1.838015678
+36.46031233,0.1509729337,-1.439375456,-0.3041563708,1.478886617
+36.47035333,0.353432392,-1.170883519,-0.3591201979,1.274696037
+36.48039333,0.6816339022,-1.056811504,0.3060707492,1.29427765
+36.49043433,-0.09493997061,-1.020825766,0.2532142586,1.056038022
+36.50047433,0.7342543115,-0.8952390488,0.2401872468,1.182485629
+36.51051533,0.1932487231,-0.7235074946,-0.03508329391,0.7496926045
+36.52055633,0.3101006502,-0.9730660739,0.135113951,1.0301824
+36.53059633,0.4925437188,-1.052078987,0.613530212,1.313730883
+36.54063733,0.08757250629,-0.5882698019,0.266869846,0.6518817518
+36.55067733,0.4963527047,-0.2785998174,-0.3400939429,0.6630593908
+36.56071833,0.2329676714,-0.2011429759,0.1467288601,0.3409718332
+36.57075933,0.423031873,-0.7593336772,0.06039238214,0.8713155793
+36.58079933,0.3096380989,-0.4751479964,0.09724855185,0.5754117236
+36.59084033,0.5279896497,-0.2608768519,0.1451910424,0.6065560493
+36.60088033,0.5723016407,0.01960842756,-0.1631133431,0.5954155029
+36.61092133,0.3710212552,-0.4911942911,0.345591495,0.7059476502
+36.62096233,0.6433123472,-0.1612057986,0.4127122682,0.7811334725
+36.63100233,0.4224315101,0.07423351818,-0.5997033012,0.7372944089
+36.64104333,0.3566872811,-0.1796164698,-0.1845316941,0.4399316297
+36.65108333,0.7302943578,-0.3893357213,0.3523350888,0.8994732724
+36.66112433,0.5593870416,-0.01360075152,-0.05546493351,0.5622945862
+36.67116533,0.6026008158,0.03471888447,-0.2538445884,0.654805482
+36.68120533,0.8128930762,-0.02143748229,0.1532841736,0.8274966809
+36.69124633,0.4848473578,-0.09973697151,-0.3778394741,0.622725535
+36.70128633,0.7485827672,-0.326108207,-0.3548131388,0.8902893269
+36.71132733,0.7371048291,-0.04202057675,-0.1358366668,0.7506935846
+36.72136833,0.5573131439,0.07218466295,-0.4343335176,0.710249372
+36.73140833,0.9146021035,0.1107989077,-0.1463464522,0.9328401201
+36.74144933,0.6724934616,0.0669533601,-0.4056254429,0.7882018829
+36.75148933,0.6319736458,0.1359347904,-0.005666536689,0.6464526788
+36.76153033,0.6956051662,0.0890817092,-0.02348768055,0.7016792496
+36.77157133,0.2398982664,-0.04844167834,0.116159032,0.2709071707
+36.78161133,1.120950855,0.05952849258,-0.1276985121,1.129770495
+36.79165233,0.3405659228,-0.03462989716,-0.08188382328,0.3519791728
+36.80169233,1.172491211,0.3174215835,0.09743858635,1.218600172
+36.81173333,0.5532900402,0.1192639766,-0.3520748878,0.6665661943
+36.82177333,0.5431021075,-0.3350795169,-0.2000016725,0.6687591875
+36.83181433,1.130909906,-0.2280435666,0.05937672079,1.155199844
+36.84185533,0.4176130024,-0.003176043089,-0.5178259099,0.665247608
+36.85189533,1.005253242,-0.8092183936,-0.08060854554,1.293006661
+36.86193633,1.18683677,-0.8807017013,0.2904159987,1.506173449
+36.87197633,0.9387836292,-0.6385744945,-0.8152573979,1.397761322
+36.88201733,1.060583689,-0.4332465202,-0.4747822165,1.240144533
+36.89205833,0.8626580708,-1.033599301,-0.0443721807,1.347024629
+36.90209833,0.7154174332,-1.127978916,0.3168734801,1.372795448
+36.91213933,1.283960849,-1.086914286,0.068584916,1.683639516
+36.92217933,0.8625762098,-1.049760274,-0.1038062042,1.362648186
+36.93222033,0.9942640579,-1.273594028,-0.292666592,1.642028166
+36.94226133,0.9968670921,-1.194573148,0.4555343521,1.62119109
+36.95230133,0.7837139352,-1.303485872,-0.482217536,1.595561563
+36.96234233,0.9187010016,-1.384652826,0.3948712438,1.707980761
+36.97238233,1.089008759,-1.094793336,0.2332594657,1.561704999
+36.98242333,0.9222837368,-1.114279913,-1.101021352,1.817821508
+36.99246433,0.870348402,-1.228200777,-0.3200479335,1.538965292
+37.00250433,1.16932107,-0.8343490686,0.06808731794,1.438084148
+37.01254533,0.8917600286,-0.6639565998,-1.353676617,1.751717642
+37.02258533,0.2906225881,-1.034421639,-0.419785645,1.15356387
+37.03262633,1.353665507,-1.128629565,0.32827672,1.792757821
+37.04266733,0.4391962448,-0.6577872757,-0.6980844587,1.05494045
+37.05270733,0.6330585236,-0.2321935,-0.5564151943,0.8742281076
+37.06274833,1.147716777,-0.7469293208,0.1356454629,1.376065734
+37.07278833,0.3256960149,-1.345251656,0.1017017913,1.387848394
+37.08282933,0.9733422817,-1.087438124,0.136609084,1.465803163
+37.09286933,0.6829612201,-0.8778884596,-0.1236516541,1.119113
+37.10291033,0.5487949567,-0.9618896328,0.5896817583,1.254644231
+37.11295158,1.11151016,-1.167363276,0.3710631359,1.654049487
+37.12299158,0.3677674989,-1.7123362,-0.5386700642,1.83235194
+37.13303258,0.7106713213,-1.596829133,0.8663901293,1.950781603
+37.14307258,0.911165037,-1.413698285,0.2446597821,1.699594944
+37.15311358,0.2116803529,-1.466301884,-0.1823027354,1.492676815
+37.16315458,0.9628190477,-1.390218937,0.8259420151,1.881996127
+37.17319458,0.6817145207,-1.311704279,0.0157506448,1.478360878
+37.18323558,0.5187013111,-1.165752733,-0.7338062686,1.471904251
+37.19327558,0.9156233928,-1.451579179,0.05933286667,1.717256155
+37.20331658,0.4808598125,-1.687530996,0.1360413194,1.75996996
+37.21335758,0.7684420312,-0.9838962867,-0.493213225,1.342316782
+37.22339758,0.6151911867,-0.7707516083,-0.2344587296,1.013651387
+37.23343858,0.5444457977,-1.325636732,0.1606510806,1.442061976
+37.24347858,1.096889344,-1.736886173,0.3559053987,2.084852145
+37.25351958,0.2960490966,-1.299674949,0.1684506816,1.343568261
+37.26355958,1.017485471,-1.123420281,-0.09698718131,1.518800949
+37.27360058,0.6025057986,-1.512456003,0.02661711037,1.628264374
+37.28364158,0.391171345,-1.406323923,0.22822092,1.477446035
+37.29368158,0.9378781879,-1.538706055,-0.5108150983,1.873009312
+37.30372258,0.7770195311,-1.483387448,0.3256174064,1.705937973
+37.31376258,0.9141281135,-1.063149521,0.1694844693,1.412317987
+37.32380358,0.2967813873,-1.172652302,-1.048378869,1.600715736
+37.33384458,0.5092418684,-1.783363352,0.02893553138,1.854871799
+37.34388458,0.9781190184,-1.903155844,0.4911643606,2.195441051
+37.35392558,0.3026160314,-1.424587116,-0.08304157197,1.458739462
+37.36396558,0.9013695621,-1.075540648,-0.1626654464,1.41269771
+37.37400658,0.5662244833,-1.458346455,0.7109342998,1.71837485
+37.38404758,0.3523723648,-2.088997899,-0.3529180562,2.147703345
+37.39408758,0.5210393934,-1.737905928,0.4833630055,1.877615205
+37.40412858,0.5778333259,-1.106998595,0.4989183533,1.34471438
+37.41416858,0.6546446896,-1.075829793,-0.2080790162,1.276427158
+37.42420958,0.6085909593,-1.129690543,0.1804947764,1.29582485
+37.43425058,0.5103546301,-1.49042311,0.08603125334,1.577727566
+37.44429058,0.7464673908,-1.729902551,-0.1205356729,1.887936771
+37.45433158,0.6058754028,-1.722147389,0.1860256577,1.835070075
+37.46437158,0.4896060777,-0.8548647556,0.4161095005,1.069418056
+37.47441258,0.8426852247,-0.8460737593,-0.8725261974,1.478939201
+37.48445258,0.805129728,-1.562152074,-0.2023341268,1.769037049
+37.49449358,0.5171390813,-1.849228143,0.8501547503,2.09996206
+37.50453458,0.9206060245,-1.317265712,-0.433404395,1.664495052
+37.51457458,0.5052249774,-0.7684310677,-0.8909782559,1.280461181
+37.52461558,0.4907888963,-1.022013335,-0.3453242773,1.1851725
+37.53465558,0.8306303857,-1.353507047,-0.2685123289,1.610598347
+37.54469658,0.7567228223,-1.726943422,-0.6888224691,2.007346359
+37.55473758,0.783296371,-1.100477634,0.05259102702,1.351802516
+37.56477758,0.9137478983,-0.4839236073,-0.325372408,1.083967012
+37.57481858,-0.2812509815,-0.6576449691,-0.8857935297,1.138520618
+37.58485858,1.066887719,-1.09141043,0.7229129058,1.688795192
+37.59489958,-0.3483088423,-1.684831921,0.1443490434,1.726503489
+37.60494058,0.5619085072,-0.915655991,1.338266864,1.716136727
+37.61498058,0.992252031,-0.6622717977,-0.08377364337,1.195903863
+37.62502158,-0.3543504414,-1.244680424,0.8608118856,1.554281408
+37.63506158,1.242706988,-1.693184522,1.219787657,2.428801436
+37.64510258,0.3197337187,-1.923896648,-0.2486540151,1.966071409
+37.65514258,-0.2141221319,-0.8242697845,0.7820212394,1.156211998
+37.66518358,1.56702032,-0.575297754,-0.361133979,1.707904546
+37.67522458,0.01207475385,-1.082462509,-1.38960074,1.761493996
+37.68526458,0.8031508841,-1.358071969,0.7026476258,1.7271724
+37.69530558,0.852729791,-1.808214603,0.1114017373,2.002298303
+37.70534558,0.08047672737,-1.044627003,-0.7859523225,1.309749263
+37.71538658,0.927263445,-0.5516125106,-0.1206830227,1.085660283
+37.72542758,0.8528069012,-0.8782968877,-0.4548929125,1.30599104
+37.73546758,0.3396040924,-1.370497156,-0.6838985288,1.56885646
+37.74550858,0.7191207672,-1.313571003,0.4049652922,1.551322128
+37.75554858,0.7032713044,-0.8475904539,-0.5172411883,1.216773829
+37.76558958,0.4155072008,-1.013938769,-0.06080285668,1.09745845
+37.77563058,0.206281911,-1.046342284,0.6749446875,1.262115182
+37.78567058,0.5771177364,-0.9864222108,-0.06313121796,1.144586917
+37.79571158,0.3910155167,-0.9720006381,-0.01352227092,1.047788732
+37.80575158,0.7317550653,-1.444378918,0.4295972729,1.675186483
+37.81579258,0.5063751247,-0.9727111479,0.1274119985,1.104000254
+37.82583258,-0.01000083326,-0.4696832252,-0.3781809515,0.6030946698
+37.83587358,0.2716868919,-0.7178278016,0.2951861572,0.8223292451
+37.84591458,0.6874427455,-1.044711203,0.0398604691,1.251234544
+37.85595458,0.3813625677,-1.485512472,0.1437982357,1.540409895
+37.86599558,0.4629232227,-1.522434569,0.4628451258,1.657205642
+37.87603558,1.179020066,-0.9467275102,0.1229435563,1.517068361
+37.88607658,0.5427649424,-0.918659998,-1.130488395,1.5545205
+37.89611758,0.1676319617,-1.281221136,-0.4111557394,1.355978288
+37.90615758,1.07908523,-1.368265127,-0.2132403535,1.755575644
+37.91619858,0.1826295583,-1.113564287,-1.155047286,1.614779616
+37.92623858,0.642471079,-0.9300725204,0.08490624905,1.133584162
+37.93627958,0.9759852232,-1.243508349,0.1210192376,1.585403995
+37.94631958,-0.03804048897,-1.225186026,0.09937869251,1.229798358
+37.95636058,0.6773175607,-0.7254954748,0.009929741621,0.9925731014
+37.96640158,1.105675005,-1.020174386,-0.4940189713,1.583454369
+37.97644158,-0.1494435122,-1.202143538,0.2863515991,1.24478098
+37.98648258,1.057017838,-0.7006994066,-0.04071123898,1.268827716
+37.99652258,-0.1698234068,-0.3886957436,-0.7333004844,0.8471445986
+38.00656358,1.033805708,-0.5385219835,-0.3660994345,1.221797431
+38.01660458,0.4630035488,-0.9610531886,-0.0203383702,1.066962589
+38.02664458,-0.02768899408,-1.167719079,0.394887616,1.232992602
+38.03668558,0.4623149295,-0.4498792905,0.9872216713,1.179293474
+38.04672558,0.5952576997,-0.9523743126,0.6163076395,1.281086908
+38.05676658,0.3530892335,-1.328738827,-0.1162391388,1.379757375
+38.06680658,0.650292607,-0.8574387,0.5070635247,1.189619694
+38.07684758,0.4208204925,-0.754862823,-0.7311346757,1.132018411
+38.08688858,0.4818886301,-0.9204171594,-0.3754274976,1.104685568
+38.09692858,0.8500601716,-1.38355238,-0.3312745875,1.657275577
+38.10696958,0.2698709842,-0.7264554414,0.04206311524,0.7761038347
+38.11700979,0.6433490384,-0.802666223,-0.9615763682,1.408119371
+38.12705079,0.1436871294,-1.468667813,0.6139459491,1.598299335
+38.13709179,0.660696704,-1.185273297,0.3012251616,1.390010619
+38.14713179,0.3524387673,-0.484846371,-0.2294026423,0.641805781
+38.15717279,0.5863850981,-0.7293799263,0.02345318198,0.9361584331
+38.16721279,0.2001075071,-1.479467475,0.672039206,1.637224394
+38.17725379,0.1639230911,-0.7605808152,0.4681760323,0.9080433654
+38.18729479,0.7799088597,-0.6099891382,-0.03022016466,0.9905845933
+38.19733479,0.4339042954,-1.640606944,-0.1358232182,1.702442959
+38.20737579,0.6056382251,-1.230995454,0.8169735557,1.596744581
+38.21741579,0.6941033819,-0.3203029817,-1.089399426,1.330851086
+38.22745679,0.1059622097,-0.630790681,-0.9101167774,1.112401646
+38.23749679,0.7912423716,-1.581350383,0.6451858681,1.882285401
+38.24753779,0.3629451175,-0.8484718486,0.3844333792,0.9997112879
+38.25757879,0.2527974252,-0.1307886559,-1.79663887,1.819044651
+38.26761879,0.5110340034,-0.7085278782,0.596473884,1.057803669
+38.27765979,0.4193230572,-1.487882641,0.7096601915,1.700953899
+38.28769979,0.6876793385,-0.644112027,-0.3911758035,1.020196885
+38.29774079,0.3721247344,-0.2408981951,-1.123734276,1.208009719
+38.30778179,0.4407331854,-0.9629075599,0.3664362341,1.120585661
+38.31782179,0.5096817252,-1.348432395,0.1822851938,1.453022118
+38.32786279,0.3392751134,-0.6099213105,-0.2050010419,0.7274180606
+38.33790279,0.6683979256,-0.0730768567,-0.4823789191,0.8275176346
+38.34794379,0.2576964052,-0.9351472458,0.2730825126,1.007711202
+38.35798379,0.1347042621,-1.533605382,0.5206296498,1.625160281
+38.36802479,0.2168223943,-0.7441344249,0.5544212937,0.9529590568
+38.37806579,0.6714386239,-0.837985379,-0.4861895496,1.178740684
+38.38810579,0.1619318767,-1.37420546,0.8589705974,1.628647619
+38.39814679,1.084819741,-1.230058292,0.2380565214,1.657271305
+38.40818679,0.2970370203,-0.6466114193,-1.182756656,1.380308163
+38.41822779,0.5859161149,-0.3914837325,-0.6710668141,0.9730816386
+38.42826879,0.5790267792,-1.433345515,0.03308822393,1.546236142
+38.43830879,-0.3379435562,-1.163754374,-0.1415996826,1.220073998
+38.44834979,0.9269623134,-0.1423923092,-0.3567485672,1.003396353
+38.45838979,-0.01783968593,-0.1071129326,-0.1940304959,0.2223494278
+38.46843079,0.3924554301,-0.9803772131,1.049271154,1.488667424
+38.47847079,0.8999136785,-0.9877490171,1.07975152,1.717951133
+38.48851179,-0.06614974254,-0.6651272855,-0.3445676476,0.7519953179
+38.49855279,0.3548875081,-0.6021404938,0.6349894935,0.9443145527
+38.50859279,0.3150353713,-0.7960733411,0.7461906713,1.135685065
+38.51863379,-0.09941366617,-0.7900349946,0.2909937036,0.8477710217
+38.52867379,0.8336235023,-0.7102463749,0.3180856079,1.140419445
+38.53871479,0.4630140007,-1.342515305,0.02307896018,1.42030347
+38.54875479,0.2628764535,-1.104401116,0.2512256205,1.162721018
+38.55879579,0.4267965297,-0.6595869756,-0.2788040131,0.8336317735
+38.56883679,0.2311939733,-0.657798897,-0.7273947966,1.007597753
+38.57887679,0.5686245095,-1.077739713,-0.6285862076,1.371122657
+38.58891779,0.7541422268,-1.040125305,-0.2576645744,1.310336667
+38.59895779,0.3158059978,-0.8915062594,-0.8132898098,1.247380116
+38.60899879,0.9044128186,-0.6969879596,-0.4261895156,1.218766699
+38.61903979,0.5385761433,-1.054714108,-0.2053489512,1.201937729
+38.62907979,0.07853169677,-0.9098317257,-0.4590134454,1.022083333
+38.63912079,0.8493002529,-0.7477419376,-0.6784068239,1.319342542
+38.64916079,0.04368072004,-0.7689190178,-0.9232227266,1.202283105
+38.65920179,0.4317276694,-0.9337128507,0.2879899889,1.068244683
+38.66924179,0.5491150917,-0.5616938413,0.3943297917,0.8789330691
+38.67928279,-0.1081956724,-0.09939915776,-0.321403318,0.3533929668
+38.68932379,0.6385886009,-0.5868620847,0.115314694,0.8749285607
+38.69936379,0.05323155752,-1.096785483,1.10734687,1.559483595
+38.70940479,-0.205714658,-0.2844098484,0.5890058202,0.6856641587
+38.71944479,0.3041515834,0.5293059676,0.2682965666,0.6668253449
+38.72948579,0.2842859788,-0.3872401889,0.8192264879,0.9496870643
+38.73952679,0.2164456144,-1.295580582,0.5299308157,1.416405457
+38.74956679,0.1107955638,-0.3833734982,0.2084222478,0.4502118718
+38.75960779,0.2899005849,0.2168004307,-0.937510398,1.004972896
+38.76964779,0.07043935587,-0.3999540091,-0.2573803997,0.4808009801
+38.77968879,0.2833802634,-0.8214677256,1.317699283,1.578431183
+38.78972879,0.6386692925,-0.1431349421,-0.3792498225,0.7564499353
+38.79976979,0.4211350727,-0.3586862614,-0.7479430819,0.9302846002
+38.80981079,0.6962007051,-0.640544056,0.3846912414,1.021263659
+38.81985079,0.2248087225,-0.1092518989,-0.8091476423,0.8468735715
+38.82989179,-0.004413130054,0.3547909194,-1.164232092,1.217100011
+38.83993179,0.6436378178,-0.1854297898,0.05959365249,0.6724620814
+38.84997279,-0.1714888035,-0.2827896215,0.6668515563,0.7443583666
+38.86001279,0.4328068095,0.2589861913,-0.2352065885,0.5565228845
+38.87005379,0.2678315485,0.4063108462,-0.6434474909,0.8067508387
+38.88009479,0.1411909896,-0.06212366961,0.7282800651,0.7444367663
+38.89013479,0.3373820043,0.03054855891,0.5495248353,0.6455519932
+38.90017579,0.05095517251,0.5050776641,-0.5351295751,0.7376066286
+38.91021579,0.1292454478,0.5921575059,-0.1137593347,0.6166815092
+38.92025679,0.1367791649,0.2207945906,0.03920733511,0.2626709088
+38.93029679,0.2655375031,0.2960843261,0.2881355846,0.4911193427
+38.94033779,0.06251443264,0.3207885199,0.3957646984,0.5132670117
+38.95037879,0.00579858669,0.2396159373,1.162058682,1.186520038
+38.96041879,0.07272981531,0.2640340926,0.2096349603,0.3448919318
+38.97045979,-0.3325779319,0.2477121017,0.3138738585,0.5200828445
+38.98049979,0.3590380445,0.3465394749,0.3535846388,0.6115717635
+38.99054079,0.0373178188,0.415218129,-0.1915401667,0.4587879137
+39.00058179,0.3659709785,0.443258269,0.8608013606,1.035080496
+39.01062179,0.06831761145,0.3599992537,-0.3934187955,0.5376291541
+39.02066279,0.2790772974,0.4006697814,-0.008408296108,0.4883555171
+39.03070279,0.6182098849,0.363778967,-0.2271216434,0.7523980592
+39.04074379,0.09861262503,0.2243433755,-0.5754244924,0.6254340463
+39.05078379,0.6145831494,0.3072651161,0.1325838608,0.6997876672
+39.06082479,0.3646518832,0.2055576237,-0.2269362867,0.4761564982
+39.07086579,-0.01383868294,0.3184111151,0.3329644328,0.4609148087
+39.08090579,0.6726853964,0.02962692808,0.06687285125,0.6766501132
+39.09094679,-0.09746602259,0.3013354912,-0.1273476791,0.341350458
+39.10098679,0.4135092437,0.3482847957,-0.4393673855,0.6966605292
+39.11102779,0.580102338,0.08792195052,-0.1996397299,0.6197620621
+39.12106767,0.4798560283,-0.04902174041,-0.2817784917,0.5586269393
+39.13110867,0.776311214,0.4175601582,-0.3801023465,0.9599444675
+39.14114967,0.1652585952,0.5163644348,-0.2306475145,0.5891866502
+39.15118967,0.1269849325,0.228394765,-0.1090850705,0.2831764368
+39.16123067,0.4302603471,-0.006516246758,-0.6623503697,0.7898572276
+39.17127067,0.05567743412,-0.09191914368,-0.02376893163,0.1100639258
+39.18131167,0.7119983469,0.2585697599,0.8902040845,1.168872653
+39.19135267,-0.05893414595,0.5798362166,-0.3935076731,0.7032293797
+39.20139267,0.3001797342,0.3720852657,0.6899299318,0.8393799071
+39.21143367,0.3727667952,0.135259839,0.3518907005,0.5301673064
+39.22147367,0.2255466411,0.1746383148,-0.284883948,0.403148474
+39.23151467,0.2573433064,0.07545104552,-0.4230396205,0.5008801834
+39.24155467,0.4557371774,-0.1876634993,0.1055872661,0.5040462623
+39.25159567,0.05062113205,0.132442614,-0.1919038635,0.2386014205
+39.26163667,0.08681055928,0.4182189201,0.2215287817,0.4811633189
+39.27167667,0.4671276265,-0.3820550973,0.5154151028,0.7936164345
+39.28171767,0.2455324973,-0.1909905285,1.172963154,1.213509848
+39.29175767,0.5368395934,0.6029209509,0.27594414,0.8531445308
+39.30179867,-0.2726016157,0.4504580918,-0.6252164572,0.8173859258
+39.31183867,0.3216976523,0.0836903571,1.155981671,1.202824625
+39.32187967,0.3005194209,0.3693697457,0.3123611838,0.5694869976
+39.33192067,0.1122611227,0.1729267982,-0.7705589426,0.7976636642
+39.34196067,0.5896821237,0.154431982,1.159830893,1.310260258
+39.35200167,0.06755964328,0.5421471475,-0.4342323607,0.697886508
+39.36204167,0.1872912875,0.5046454818,-0.1797176814,0.5674887961
+39.37208267,0.01085731559,-0.02585032113,1.188577559,1.188908211
+39.38212267,-0.3620347791,0.259446221,0.2579241908,0.5146905974
+39.39216367,1.031183451,0.6921491694,-0.4381236827,1.316951838
+39.40220467,0.4481874352,0.5403207332,-0.7085919052,0.9974572472
+39.41224467,0.1078665382,-0.5375514553,0.1060965586,0.5584382123
+39.42228567,0.5614933183,0.4461576474,0.03751281202,0.7181494301
+39.43232567,0.4291392897,0.7771570869,-2.70946934,2.851202864
+39.44236667,0.05916961972,0.814366136,0.2294710547,0.84814516
+39.45240667,0.6087513558,-0.4231446146,0.03947513759,0.7424202748
+39.46244767,0.3443782343,0.05121791806,-0.7566770679,0.8329344683
+39.47248867,0.2458377036,0.5804676793,-1.100106847,1.267917181
+39.48252867,0.306205564,0.06495014057,0.03494529963,0.3149627631
+39.49256967,0.2745238147,-0.1451171848,-0.1092242342,0.3291690379
+39.50260967,0.2163288893,-0.009733530991,0.1513136619,0.2641756126
+39.51265067,0.696660077,0.3731585587,-0.2614044535,0.8324150774
+39.52269067,0.34730451,0.5001429795,-0.479558807,0.7750742365
+39.53273167,0.1786892658,0.0990291021,-0.2761388522,0.3434956805
+39.54277267,-0.005867621521,-0.4408587544,0.9846056271,1.078813752
+39.55281267,0.04715462852,0.2392107618,0.6830571145,0.725267102
+39.56285367,-0.2183233928,0.1693122688,0.2677814269,0.384757899
+39.57289367,0.4286406684,-0.2592451864,0.9921865422,1.111474257
+39.58293467,0.1521971945,-0.340910872,0.5208799106,0.6408588689
+39.59297467,0.2355061121,0.07123527613,-0.117135517,0.2725038032
+39.60301567,0.3875156658,0.6675675479,0.5748368472,0.9624199827
+39.61305667,0.08852421373,-0.02656327944,-0.6333487648,0.6400568741
+39.62309667,0.1547342831,-0.6742371013,0.5483559769,0.8827415503
+39.63313767,0.6137073096,-0.5675854227,0.5355774719,0.9927905631
+39.64317767,-0.1616868052,0.2115157172,0.3333287144,0.4266023364
+39.65321867,0.5259119513,0.4547737389,-0.31667409,0.7639928098
+39.66325967,0.2099899776,-0.2747858796,-0.4914309937,0.6009222012
+39.67329967,0.1275000265,-0.677234384,-0.1893983316,0.7146848226
+39.68334067,0.7832632611,-0.1233379145,0.02687497258,0.7933699273
+39.69338067,0.06443133265,-0.08012742933,-0.141493848,0.1749065767
+39.70342167,0.4428123457,0.06526559785,0.2808932233,0.5284348348
+39.71346167,-0.08625043256,-0.07472818349,0.1708112025,0.2054261557
+39.72350267,0.06618119873,0.2229757483,-0.2737444174,0.3592132256
+39.73354367,1.010158471,-0.2370903421,-0.6154480988,1.206403054
+39.74358367,-0.4863301386,-0.01310773987,0.3847117066,0.6202353696
+39.75362467,0.7076368356,0.7687311029,-0.350973857,1.102215972
+39.76366467,-0.06165682426,0.2235933604,-1.043587076,1.069050766
+39.77370567,0.1296891327,-0.6985553788,1.234072405,1.423985109
+39.78374567,0.03129785218,-0.1758698846,0.7773001975,0.7975621411
+39.79378667,-0.4296717883,0.83993104,-0.3702421868,1.013499519
+39.80382767,0.5447039522,0.8281521164,0.3761005121,1.060183908
+39.81386767,0.2857789922,-0.1036680272,-0.04822023332,0.3078016945
+39.82390867,-0.3495602927,-0.1983924822,-0.1559832484,0.431141217
+39.83394867,0.5350186973,0.5080824386,0.9862089336,1.231665877
+39.84398967,-0.2340008378,0.4617508925,-0.3305308217,0.6141831184
+39.85402967,-0.02972120987,0.1344644715,-0.3203549123,0.3486994612
+39.86407067,0.6113680944,0.02183116436,-0.1187364846,0.6231740523
+39.87411167,0.1191248311,-0.2158621353,-0.4607693642,0.5225854895
+39.88415167,0.8055992594,0.09806390952,0.0407714653,0.8125693875
+39.89419267,0.008183982298,0.1162082948,-0.2513665384,0.277049602
+39.90423267,0.09512681656,0.243142393,-1.04104763,1.073288173
+39.91427367,0.799902975,-0.3753008689,-0.2707775402,0.9241298545
+39.92431367,-0.4801165948,-0.2596587673,-0.4634321862,0.7160335267
+39.93435467,0.5218368074,0.6614577922,-0.04376699388,0.8436560995
+39.94439467,0.5686075891,0.5624190788,-1.165933047,1.413870461
+39.95443567,0.1242599838,-0.5488725784,0.3458265531,0.6605283157
+39.96447667,0.5892881676,-0.3839357446,1.503724356,1.660076546
+39.97451667,-0.290557209,0.5361404856,0.02338184595,0.6102596355
+39.98455767,-0.4977685349,0.7367878369,-0.481866703,1.011348283
+39.99459767,0.5272005314,-0.58123604,1.282580321,1.503591705
+40.00463867,-0.6897724955,-0.7042779757,0.8115806687,1.276893396
+40.01467867,0.7683078376,0.1262169373,0.7219147861,1.061785575
+40.02471967,0.2971882804,-0.05258766487,-0.6586976141,0.7245473644
+40.03476067,-0.09591365992,0.3011109947,0.9390031922,0.9907543874
+40.04480067,0.2677405329,-0.3888979841,-0.3850338882,0.6092435721
+40.05484167,-0.2992957631,-0.466820063,0.1988082558,0.5890871307
+40.06488167,0.7634998915,-0.4296124025,0.7920240712,1.181016947
+40.07492267,-0.5528359308,-0.07877036367,-0.7111512315,0.9041948964
+40.08496267,0.6153340781,0.3438325064,-0.4141875207,0.8175623049
+40.09500367,0.2299850615,-0.8529587826,0.4775268996,1.00422296
+40.10504467,-0.07388886593,0.01319731191,1.08377265,1.086368672
+40.11508467,0.8177459729,0.562464285,0.06753884912,0.9948045256
+40.12512596,-0.7307470053,0.3019810238,-1.266406338,1.49297312
+40.13516596,0.3784770399,0.3340376162,0.5984560901,0.7829276406
+40.14520696,0.7223116659,0.5151741245,-1.06871607,1.388989762
+40.15524696,-0.1482284882,0.07779603481,-0.2317350966,0.2858759569
+40.16528796,0.3011427158,-0.0631133474,0.8683477771,0.9212481164
+40.17532896,0.4048036532,0.8181689458,-0.7226053423,1.16422717
+40.18536896,0.08001214782,0.5330042219,-1.168697026,1.286991912
+40.19540996,0.245324044,-0.9939856573,1.186713467,1.567316249
+40.20544996,-0.1099042471,-0.6640133909,0.9558765024,1.169056292
+40.21549096,0.4593180122,0.311302655,-0.7728463733,0.9514062729
+40.22553096,0.08758549808,-0.0472169973,-1.418519899,1.422005404
+40.23557196,0.3316171247,-0.5970830542,0.7965767133,1.049291452
+40.24561296,0.6110626139,0.0008624643087,-0.3151953292,0.6875655296
+40.25565296,-0.56226939,0.4273998892,-1.534056787,1.688830293
+40.26569396,0.3465464184,-0.05752030291,0.5707104671,0.6701592666
+40.27573396,-0.2476199167,-0.9871644417,0.05133855343,1.01904117
+40.28577496,0.07241756486,-0.5272416447,0.146766867,0.5520584832
+40.29581496,-0.02412599094,0.2709437839,-0.1011112225,0.2902000633
+40.30585596,-0.5979922232,0.6350941586,-0.7712465751,1.164371319
+40.31589696,0.6224298935,-0.04999373037,0.06138933241,0.6274448148
+40.32593696,-0.3843717641,-0.6660337501,-0.09144928336,0.7744065991
+40.33597796,-0.8800673515,0.1072192605,0.624106071,1.084215339
+40.34601796,0.6729977839,0.7009131955,0.2549999982,1.004604561
+40.35605896,-1.042852885,-0.1325716547,-0.7925058818,1.316504066
+40.36609896,0.3137634192,-1.056642958,1.869971725,2.170653376
+40.37613996,0.3001573686,-0.01309293911,0.1968915385,0.3592104521
+40.38617996,-0.2017784952,0.7907058895,-0.9623166257,1.261738346
+40.39622096,0.04140579227,-0.102990006,1.889310222,1.892568227
+40.40626196,-0.387681946,-0.3482687889,0.9712254435,1.10221019
+40.41630196,0.3750378538,0.42715818,-0.1274763179,0.5825527565
+40.42634296,0.1091007849,-0.3084905463,0.291746825,0.4383897904
+40.43638296,0.109305072,-0.558183173,0.8247719872,1.001880674
+40.44642396,0.02656065276,0.3933331703,-0.7751770735,0.8696642722
+40.45646396,0.2751035479,0.7486486946,-1.717431902,1.893602168
+40.46650496,-0.3154263673,-0.2371399338,0.6533503354,0.7632796356
+40.47654596,-0.5230873807,-0.6870561714,0.7994447726,1.176766134
+40.48658596,-0.144021179,-0.4392579329,0.4798932678,0.6663236301
+40.49662696,0.02163642924,-0.3438169016,-0.02374671221,0.3453144991
+40.50666696,-0.2334671515,0.4588796538,-0.09912316918,0.5243117871
+40.51670796,0.0575350991,0.07816342268,-0.2519956988,0.270040072
+40.52674796,-0.2128666067,-0.8360357711,1.667708935,1.877637104
+40.53678896,-0.316113744,-0.001350999177,0.500807004,0.5922308499
+40.54682996,-0.6537839064,0.8563590847,0.1392625505,1.086360132
+40.55686996,0.5112213701,-0.304120922,0.2881443554,0.6609568776
+40.56691096,-0.4408339037,-0.3568993523,0.7111810523,0.9096648655
+40.57695096,0.9266122844,0.5089313447,-0.7383963329,1.289515639
+40.58699196,0.1950256737,0.0815798777,-1.416052374,1.431745304
+40.59703196,-0.01481031203,-0.8575184414,0.5138024408,0.9997750601
+40.60707296,0.6952433697,0.4912665407,-0.8541103917,1.205906596
+40.61711396,0.2678609673,0.8610467244,-3.561162493,3.67355812
+40.62715396,0.2045210768,-0.1312405726,-0.6159603149,0.6621631734
+40.63719496,0.001155944285,-0.9945049632,0.8130617684,1.284566424
+40.64723496,-0.395073594,-0.1242634922,-0.09531370819,0.4249814857
+40.65727596,0.3133400077,0.6270494132,-0.567776919,0.9020773563
+40.66731596,0.2259289576,0.1144010666,0.02041672289,0.2540636544
+40.67735696,-0.88330437,0.1113064277,0.5405095983,1.041521174
+40.68739796,-0.06765173692,-0.02072794095,-0.9315924311,0.9342755818
+40.69743796,-0.1150878769,-0.3862931957,0.06868958116,0.4088837378
+40.70747896,0.2182708045,-0.3783277531,-0.08094943821,0.4442148629
+40.71751896,0.07452020077,0.2607899112,-0.5580407202,0.6204627978
+40.72755996,0.1560017584,-0.1457448103,0.284575215,0.3557543413
+40.73759996,-0.03766680849,0.6504625417,-0.3871692914,0.7579052492
+40.74764096,0.301170618,0.2339134037,-1.765426433,1.806142218
+40.75768096,-0.2374128526,-0.3330039015,-0.5678576106,0.6997990618
+40.76772196,0.1926221392,-0.1990922112,0.7039036077,0.7564530957
+40.77776296,0.1628014855,0.725643117,-0.64727157,0.9859121372
+40.78780296,-0.05032294689,0.3916668966,-0.002663991451,0.3948954972
+40.79784396,0.3910167593,-0.3363774161,1.282403736,1.382245714
+40.80788396,-1.017355151,0.564728802,0.04401783943,1.164417319
+40.81792496,0.4839851493,0.5284312972,0.0276292634,0.7171085251
+40.82796496,-0.7571539083,0.07380589485,1.567705759,1.74253571
+40.83800596,-0.462557991,-0.4712099332,1.002321521,1.200269606
+40.84804696,0.1971957399,0.159457335,1.705870203,1.724617624
+40.85808696,-0.410503044,0.2453640792,0.5190848154,0.7058082785
+40.86812796,-1.125611671,-0.4671124238,2.171226123,2.489863154
+40.87816796,0.2084692448,0.261536162,1.852964514,1.882906817
+40.88820896,-1.635533607,0.2507650426,0.2272900432,1.670183837
+40.89824896,0.07711939319,-0.1896902904,3.000337914,3.00731731
+40.90828996,-0.6274142063,-0.09480244227,1.815240033,1.922948898
+40.91832996,-1.373421056,-0.5886489938,0.6479972094,1.628709126
+40.92837096,0.7016167617,-0.1408168135,3.158150756,3.238211181
+40.93841196,-0.8574748065,0.5647596461,-0.5711291277,1.174906372
+40.94845196,0.04961862235,0.4968203358,-0.6371371758,0.8094666358
+40.95849296,0.792224046,-1.06945662,1.40672665,1.936552676
+40.96853296,-0.1505118442,-0.4429006387,-0.138721683,0.4879123859
+40.97857396,0.1275206928,0.4433063989,-1.006473044,1.107145013
+40.98861396,0.4505884482,1.016438015,-0.9770100939,1.480109764
+40.99865496,-0.02721253051,0.7009016472,-0.8248497552,1.08276533
+41.00869596,-0.4567963274,-0.160773324,-2.063475387,2.119538067
+41.01873596,0.5500700151,-0.172638494,-0.269742583,0.6365077629
+41.02877696,0.2325601387,-0.3607930863,-0.6854410243,0.8087553815
+41.03881696,-0.6218674645,0.2853827155,-0.3754397768,0.7804597771
+41.04885796,0.6541773509,0.4474786431,-1.566369086,1.755476361
+41.05889796,-0.4869478603,0.8580884718,-2.345690666,2.544739426
+41.06893896,0.8154044554,0.3290218746,-1.982876782,2.169087401
+41.07897896,-0.7222018844,-0.3673325026,-1.155400457,1.411190613
+41.08901996,-0.2099883879,0.257904091,0.717408337,0.7907492429
+41.09906096,-0.2666004721,0.8194906358,-0.1893930691,0.8823323912
+41.10910096,-0.2211306045,0.5594284107,-1.448679838,1.568608352
+41.11914154,0.09462636799,0.1601110537,0.08767081261,0.2056109686
+41.12918154,0.09327489372,0.04572456859,0.07165762782,0.1261972963
+41.13922254,-0.05458704717,0.06965773389,-0.4218111205,0.4309948573
+41.14926254,-0.6781949354,0.7745356339,-1.166004383,1.555448501
+41.15930354,0.4446600658,0.6340130085,0.2585948664,0.8164351622
+41.16934454,-0.2498430098,0.2444144183,-1.308916181,1.35477729
+41.17938454,-0.4389206582,0.4606408351,-0.1742593056,0.6597026821
+41.18942554,0.5349102315,0.4282381972,-0.484752304,0.8393459987
+41.19946554,-0.1242088481,0.5029609355,-1.561574954,1.645270153
+41.20950654,-0.4284279759,0.5518699343,-0.03973592341,0.6997784639
+41.21954654,-0.8664670933,-0.2516228657,0.7108471763,1.148643982
+41.22958754,0.0606791698,-0.3300006254,0.6242627764,0.7087216579
+41.23962754,-0.8639114215,0.02915995482,-0.3986421132,0.9518974638
+41.24966854,-0.506565013,0.796173694,-0.4607956767,1.050158711
+41.25970954,-0.5047202531,-0.3118711871,0.03364780247,0.5942544453
+41.26974954,-0.9531918995,-0.2573824462,0.7774949098,1.256709535
+41.27979054,-0.7342317266,-0.2478632522,1.112835651,1.356073599
+41.28983054,-0.5093534406,0.683039719,0.04286476851,0.8531245944
+41.29987154,-0.8442198265,0.646081223,-0.613916713,1.227608159
+41.30991154,-0.6536938593,-0.1007630574,1.187198201,1.35901009
+41.31995254,-0.3782602543,0.08326380271,0.4687028664,0.6080263628
+41.32999254,-0.9535229981,0.245207922,0.002887355089,0.9845513545
+41.34003354,-0.6532059091,0.3445747739,1.2802198,1.47796227
+41.35007454,-0.8761087134,0.4576593399,0.4846201569,1.100852054
+41.36011454,-1.372923312,0.5375571198,-0.5811676276,1.584816042
+41.37015554,-0.2952382888,0.3494424347,0.9098133069,1.018349604
+41.38019554,-0.5754316917,-0.1451259921,-0.5598749918,0.8158695924
+41.39023654,-1.431937797,0.55957291,1.0743867,1.875599765
+41.40027654,0.01076934697,0.9626984489,-0.25193021,0.9951749158
+41.41031754,-0.9863043894,0.2864646696,-1.900674285,2.160421508
+41.42035854,-0.1599328415,-0.3139615667,1.219198258,1.269092105
+41.43039854,-0.6629964139,0.003216955326,-0.6198650855,0.9076383189
+41.44043954,-1.298032612,0.6054787423,-2.018184024,2.474784824
+41.45047954,-0.1535053994,0.3687311932,0.9926192361,1.069962405
+41.46052054,-0.8462059794,-0.0576835864,-0.9690380001,1.287799131
+41.47056054,-0.8206841256,0.3099836693,-0.8548898256,1.22492813
+41.48060154,0.3139140581,0.5654509697,-0.376340248,0.7482705508
+41.49064154,-1.191034705,-0.1217826282,-0.05854875505,1.198675366
+41.50068254,-0.6181722435,0.3121196207,-1.051843345,1.259337128
+41.51072354,-1.041433327,1.257498982,-0.3770325583,1.675720924
+41.52076354,-0.4714107485,0.06904984273,0.9348645329,1.049270065
+41.53080454,-1.238230799,-0.8834480654,0.9822983158,1.810692126
+41.54084454,-0.9809533831,0.5821859933,0.8229774767,1.406592335
+41.55088554,-0.3817133275,1.578944985,-1.216665244,2.029543458
+41.56092554,-1.171544035,-0.1298286162,-0.1079167968,1.18364561
+41.57096654,-0.6336411987,-1.251119524,1.611702549,2.136442449
+41.58100654,-1.141827608,0.2700038805,0.3357898074,1.220420901
+41.59104754,-1.032730185,1.678774936,-0.7166341656,2.097231854
+41.60108854,-0.2667993322,0.1729149576,-0.4579276174,0.5574757116
+41.61112854,-0.7800811332,-0.9666004421,-0.1019298327,1.246287559
+41.62116954,-0.4124292995,-0.2250503404,-0.6672924364,0.8161034116
+41.63120954,-1.291935136,0.1525946772,-0.6560634434,1.456983449
+41.64125054,-0.9086078303,0.1929788011,0.4717527741,1.041805974
+41.65129054,-0.5058873938,-0.04801605586,-0.1007305688,0.5180484961
+41.66133154,-1.47061289,0.3452657686,-0.8136605233,1.715795492
+41.67137154,-0.3421683523,-0.31111178,1.213079731,1.298241948
+41.68141254,-0.9688128823,-0.8348423544,0.6544770938,1.436628144
+41.69145354,-1.047170469,-0.3083591301,0.07460579395,1.094174286
+41.70149354,-0.06541480692,0.1046426484,-0.1533824068,0.196863769
+41.71153454,-0.5643727066,0.4177102854,-1.46768095,1.626986725
+41.72157454,-1.28707376,-0.338180003,0.1018760383,1.334654752
+41.73161554,-1.005648294,-0.5480120876,0.9077118176,1.461364597
+41.74165554,-0.769751369,-0.2627540274,0.6909935403,1.067252979
+41.75169654,-1.506537744,0.02852827281,0.01709842801,1.506904839
+41.76173654,-0.2898531311,0.2536426036,1.744434344,1.786449157
+41.77177754,-2.0296988,0.1474550112,-0.9346668971,2.23942457
+41.78181854,-1.380456426,0.3249849935,1.082720152,1.784252817
+41.79185854,-1.105839165,-0.1921752474,0.07708384395,1.125057111
+41.80189954,-2.921998088,-0.08986607663,-0.9273970538,3.066955173
+41.81193954,-1.162141128,0.5278346985,0.5009409052,1.371175868
+41.82198054,-2.198115275,-0.2088949221,-0.7457176316,2.330545566
+41.83202054,-1.691236376,-0.06929849558,-0.663408131,1.818019007
+41.84206154,-0.9214587678,0.7027145764,-0.5530355036,1.284033607
+41.85210254,-1.978334665,-0.160191526,-0.5946723568,2.071980835
+41.86214254,-1.905443274,-0.4838447795,0.4205697566,2.010397663
+41.87218354,-1.684459892,0.7290032195,0.615577907,1.93592019
+41.88222354,-1.571953323,0.3761211967,-2.471835573,2.953383738
+41.89226454,-1.740890347,-1.30576994,-0.006374634504,2.17618358
+41.90230454,-1.201018753,-0.574588304,1.581671249,2.067433603
+41.91234554,-2.252002337,1.424634917,-0.2927858752,2.680825012
+41.92238554,-1.649667351,1.144129218,-1.954789097,2.80207681
+41.93242654,-1.791050102,0.04875865225,2.216544968,2.850142008
+41.94246754,-3.058057826,-1.360366562,-0.1640541601,3.351004121
+41.95250754,-2.455003193,-0.1739839748,1.453189795,2.858158792
+41.96254854,-1.992227357,1.068161315,1.152532398,2.537374502
+41.97258854,-2.026346883,0.6634123702,-1.253634265,2.473417986
+41.98262954,-2.539155444,-0.5457799861,0.9766165763,2.774701082
+41.99266954,-4.05039201,0.09115557041,1.188655912,4.222189912
+42.00271054,-2.087530101,0.9581731425,0.6842774284,2.396687984
+42.01275054,-2.671315966,-0.01991031747,-0.06158345997,2.672099911
+42.02279154,-3.718833833,-0.2973175039,1.90197646,4.18755743
+42.03283154,-3.036701748,1.04656594,-0.09623464465,3.213427902
+42.04287254,-2.982695402,1.289577246,-0.1973464519,3.255522532
+42.05291354,-2.512562892,-0.2026631058,2.436694391,3.505927007
+42.06295354,-3.378157507,0.0290267114,0.4973834592,3.414700719
+42.07299454,-2.704295139,0.4496092588,-0.1338649857,2.744682226
+42.08303454,-2.750099303,0.4353712887,0.2252973121,2.793448266
+42.09307554,-3.040825204,0.04285676513,1.25047443,3.288182009
+42.10311554,-3.547220392,0.4761410729,0.08762403488,3.580106256
+42.11315654,-2.63513515,1.179528993,-0.2497182083,2.897858707
+42.12319629,-2.413041673,1.240159357,-0.9084316099,2.861120993
+42.13323729,-2.678538154,0.5055841792,-1.28088229,3.011783765
+42.14327829,-3.010931314,-0.32029348,-0.06935382485,3.028713464
+42.15331829,-3.069928843,0.5075158069,-0.5412060016,3.158312735
+42.16335929,-2.16771487,1.00185791,-3.031631042,3.859208961
+42.17339929,-2.805817713,0.9294466491,-1.490234245,3.310178578
+42.18344029,-3.343120114,1.426411886,0.4375991875,3.660955615
+42.19348029,-3.836402044,1.204989524,-0.4173491102,4.042791198
+42.20352129,-3.645086995,1.403165549,-0.9440715587,4.018308583
+42.21356129,-3.607462209,1.544886123,-0.0007022505999,3.924341628
+42.22360229,-4.177661921,1.317128157,0.9038047081,4.472644482
+42.23364329,-3.686182103,0.8194496322,-0.1579970294,3.779470765
+42.24368329,-3.541680155,0.9427636828,1.334128205,3.900282009
+42.25372429,-3.721787261,1.497276632,-0.2330437034,4.01843839
+42.26376429,-3.449938511,1.522359725,-1.945120141,4.243011575
+42.27380529,-4.052526536,1.536954375,1.043849031,4.458118536
+42.28384529,-4.315077336,0.6571337762,1.478159745,4.608326535
+42.29388629,-4.334396829,-0.07076972812,1.62945528,4.631104484
+42.30392629,-3.501126207,1.940764258,1.313539574,4.213055522
+42.31396729,-4.042248593,1.116336818,-2.781767238,5.032316618
+42.32400829,-4.611013399,1.254320143,3.950982912,6.200405596
+42.33404829,-4.009281114,-0.01570945848,0.05637768388,4.009708254
+42.34408929,-3.329986975,1.328508446,-1.047500033,3.735104318
+42.35412929,-3.108047719,1.135648344,-1.501487796,3.633747843
+42.36417029,-3.072121549,1.208812653,-0.6338527948,3.361685322
+42.37421029,-4.1023109,1.203585388,-0.6502051181,4.324388882
+42.38425129,-2.622341442,0.7632651258,-2.349226477,3.602514862
+42.39429129,-3.830421804,1.00798952,-2.612131911,4.744618761
+42.40433229,-2.634733154,0.7907146604,-0.870842784,2.885379632
+42.41437229,-3.125154625,0.3235584921,-1.412348163,3.44470737
+42.42441329,-3.697264916,0.7036572207,-1.318354172,3.987851435
+42.43445429,-2.834788328,0.4046623334,-1.385160365,3.18095044
+42.44449429,-3.503034445,-0.126909138,-0.05263897419,3.505727758
+42.45453529,-3.534334006,-0.7815642795,0.5643551284,3.663448689
+42.46457529,-3.421951983,0.4860334655,0.7563724279,3.538090326
+42.47461629,-3.820362839,1.291882803,-1.268099107,4.227553517
+42.48465629,-3.506826365,-0.04476032618,-0.4193880343,3.532098663
+42.49469729,-4.282636107,0.1573799654,-0.4130841511,4.305389529
+42.50473729,-4.452607357,0.631654534,-1.072164173,4.623227849
+42.51477829,-3.852328397,0.4878977771,0.6375926739,3.935098822
+42.52481929,-4.267696471,0.181287403,1.61504891,4.566670699
+42.53485929,-4.180822341,1.479989046,-0.3259729171,4.447010386
+42.54490029,-3.759844449,0.7293325639,-0.648674317,3.884473534
+42.55494029,-4.45278365,0.001012957022,-0.2375489831,4.459115695
+42.56498129,-4.310013648,0.7936279625,-0.7035135984,4.43858022
+42.57502129,-3.856283162,1.26350495,-0.5997132415,4.102075152
+42.58506229,-3.585227002,0.240369351,0.4108060759,3.616682418
+42.59510229,-3.924283941,0.02316005375,0.1908899564,3.928992213
+42.60514329,-3.309573761,0.2983484411,-0.1165841246,3.325038666
+42.61518329,-3.326213475,0.365807695,-0.6867712659,3.416016118
+42.62522429,-4.18617576,0.3270018809,-0.6243990165,4.245099746
+42.63526529,-3.53984413,-0.07653307278,0.3328281927,3.556280132
+42.64530529,-3.403311059,-0.1562346421,0.1184347683,3.408953245
+42.65534629,-4.019433635,-0.3094159778,0.006441292763,4.031330609
+42.66538629,-4.076718806,-0.1954269206,0.8054516172,4.160117813
+42.67542729,-3.347730643,0.1807959811,-0.2240027386,3.360084058
+42.68546729,-3.872921121,-0.06198530987,0.07861639917,3.874214853
+42.69550829,-3.636400956,-0.6575117987,1.42781171,3.961613302
+42.70554829,-3.636989478,-0.451847171,-0.1125168014,3.666676746
+42.71558929,-3.897929078,0.3132562463,-0.4102529293,3.931957278
+42.72563029,-3.308274217,0.1136691048,0.5924036372,3.362817424
+42.73567029,-4.110603421,-1.122579159,-0.08358770192,4.26195159
+42.74571129,-3.609503472,-1.450243529,1.270353209,4.092128893
+42.75575129,-3.238369877,0.1518370243,-1.327754155,3.503287747
+42.76579229,-3.831819288,-0.2296481888,-1.088055736,3.989917622
+42.77583229,-2.988418365,-0.4950451577,0.002745267749,3.029145352
+42.78587329,-3.776882066,-0.7049936018,-0.8763637251,3.940795288
+42.79591329,-3.35026892,-0.4600433593,-0.8113695842,3.477680596
+42.80595429,-2.942941937,-0.6435021624,-0.09534762204,3.013982987
+42.81599529,-3.214106563,-1.17757997,0.07518759191,3.423861673
+42.82603529,-2.617014921,-0.7551313564,0.492694577,2.767984539
+42.83607629,-3.130285557,-0.7091055831,-1.335820389,3.476483066
+42.84611629,-3.141632956,-1.171392007,-0.6826372844,3.421697025
+42.85615729,-2.570486872,-1.717152405,-0.3173032504,3.107522565
+42.86619729,-3.006966025,-2.291837517,-0.9719452357,3.903721484
+42.87623829,-2.105100107,-1.634439593,-0.4852066326,2.708923166
+42.88627829,-1.927486693,-1.552877513,-0.6717439216,2.56473652
+42.89631929,-2.452322683,-1.63251045,-0.5478197873,2.996511878
+42.90635929,-2.609737184,-1.5750484,0.4605793297,3.082797261
+42.91640029,-2.444903444,-1.760743398,-1.486924721,3.359868344
+42.92644129,-2.708023616,-1.925228206,0.1409594125,3.325622514
+42.93648129,-1.952929244,-2.033856462,0.2237325972,2.828526297
+42.94652229,-2.937830594,-1.615967654,0.6340568626,3.412364014
+42.95656229,-1.678517513,-1.631749289,0.2551730758,2.354812112
+42.96660329,-1.650552327,-1.714713239,0.4319367439,2.418911703
+42.97664329,-3.185164015,-1.413596397,0.6141313058,3.538457551
+42.98668429,-2.190749245,-1.455865042,0.7948067611,2.747843348
+42.99672429,-2.049603307,-1.133992193,0.8552716488,2.493652261
+43.00676529,-1.974193813,-1.584312144,0.6689401817,2.618199218
+43.01680529,-1.992799214,-2.007376323,1.479715689,3.192235413
+43.02684629,-2.169219651,-2.036101939,-0.2149886709,2.98285855
+43.03688729,-1.854050927,-1.428650347,0.8631764996,2.494718485
+43.04692729,-2.098448607,-1.845412396,0.03510551333,2.794685289
+43.05696829,-2.147928185,-2.360383111,0.974422701,3.336840349
+43.06700829,-1.832762676,-2.21887596,0.3436513889,2.898366062
+43.07704929,-1.881015946,-2.342543694,-1.427424039,3.326149627
+43.08708929,-1.299868199,-2.99965262,-0.192448824,3.274844993
+43.09713029,-1.447575299,-3.095020707,0.6610967267,3.480183372
+43.10717029,-1.44415,-1.786283451,-0.9433845109,2.483214072
+43.11721129,-1.050796693,-1.941378946,-1.968271607,2.957569783
+43.12725133,-1.616266885,-2.916984977,0.03233568728,3.334991094
+43.13729233,-1.913775411,-2.961129117,0.6128443336,3.5786031
+43.14733333,-0.8141244999,-2.458419136,-1.361222448,2.925670847
+43.15737333,-1.887508841,-1.925940543,-0.4353509331,2.731568603
+43.16741433,-2.17072414,-2.862433964,1.00381373,3.730042023
+43.17745433,-1.180188778,-2.882275028,0.4596104461,3.148268834
+43.18749533,-1.476402803,-2.43252942,0.0612045604,2.846174733
+43.19753533,-1.940243271,-2.811821927,-0.9908802742,3.557067643
+43.20757633,-1.598030882,-3.563811867,0.2859118885,3.91614649
+43.21761633,-1.527683322,-3.429185866,-0.5820137197,3.798930377
+43.22765733,-1.877788868,-2.770915976,-0.2392499381,3.355787077
+43.23769733,-1.062945087,-2.894123826,0.1711748993,3.087896667
+43.24773833,-1.491911811,-3.182345949,0.6450736016,3.573408253
+43.25777933,-1.866456233,-3.636965797,-0.2626417243,4.096359329
+43.26781933,-1.538907784,-3.310540305,0.2569412738,3.659772274
+43.27786033,-1.926341223,-3.319584194,0.03901730061,3.838222515
+43.28790033,-2.223956898,-3.232831979,0.7867393577,4.002017704
+43.29794133,-1.252304608,-2.86119143,0.2615137964,3.134178154
+43.30798133,-1.824184226,-3.433765405,0.7953365189,3.968747047
+43.31802233,-1.505878471,-3.567798206,0.07432629704,3.873290385
+43.32806233,-1.758425562,-3.313554837,-0.02741700947,3.751327473
+43.33810333,-2.10006317,-3.116334978,-0.4926004368,3.790048047
+43.34814433,-2.141392313,-3.008762582,0.407082569,3.715363984
+43.35818433,-1.671466502,-2.921889037,-0.5165898085,3.405598456
+43.36822533,-2.385570138,-3.343849262,0.2808616483,4.117178164
+43.37826533,-1.426885365,-3.087126381,-0.326664058,3.416586095
+43.38830633,-1.798779682,-2.87462804,-0.2194243687,3.398123271
+43.39834633,-2.22679616,-3.231200313,-1.281717272,4.128204909
+43.40838733,-1.79569703,-3.622077909,0.6059264928,4.087924059
+43.41842733,-1.767448108,-3.677499281,0.1831318706,4.084288317
+43.42846833,-2.397949863,-2.876642698,-0.8950075722,3.850490269
+43.43850833,-1.905057943,-2.834408551,-1.504044199,3.731657347
+43.44854933,-1.937512475,-3.703560321,0.1693786347,4.183180938
+43.45859033,-1.607953022,-3.272571995,0.6731419909,3.70787817
+43.46863033,0.26343415,-1.474129113,-2.138239056,2.610463647
+43.47867133,-2.216021788,-2.943565835,-1.115787326,3.849716061
+43.48871133,-2.90425442,-3.490702668,1.052940282,4.661371267
+43.49875233,-0.5889074773,-3.084139916,0.04914584756,3.140246225
+43.50879233,-1.952114142,-3.938062027,-0.7080896294,4.452018989
+43.51883333,-1.913680978,-3.344036665,-0.5050497437,3.885850145
+43.52887333,-2.284595741,-3.588362863,0.1157526505,4.25548169
+43.53891433,-1.529712306,-3.730042653,0.7811529279,4.106511637
+43.54895433,-2.385602737,-2.868350177,0.8190627658,3.819606913
+43.55899533,-1.212102223,-3.000006961,0.05598533571,3.236103819
+43.56903533,-1.384636746,-3.961332484,-0.4758335459,4.223244195
+43.57907633,-2.261025468,-4.503232258,2.277867057,5.529920005
+43.58911733,-0.6043150733,-3.527150702,-0.5750391608,3.624452899
+43.59915733,-1.550211329,-3.11884548,0.06367325485,3.483447513
+43.60919833,-1.747345527,-3.961240098,1.276448931,4.513752472
+43.61923833,-1.139579938,-4.570913486,1.761594753,5.029424282
+43.62927933,-1.192726158,-3.906547874,-0.4374986154,4.107933424
+43.63931933,-1.20796371,-3.517760658,0.7288700491,3.790127692
+43.64936033,-0.6893629711,-3.62302662,-1.366619428,3.933089352
+43.65940033,-1.38002534,-4.265133052,-0.5729698312,4.519305734
+43.66944133,-1.612948591,-4.380982766,-1.226948158,4.827008901
+43.67948133,-1.261749469,-4.209928904,-0.2190612566,4.400397815
+43.68952233,-0.6768951724,-3.598962988,-0.6284283328,3.715594681
+43.69956333,-0.947729723,-3.997131769,-0.3840843004,4.125866546
+43.70960333,-0.8779307789,-4.104914665,-0.7374151701,4.262026278
+43.71964433,-0.9184163153,-4.059448763,-1.531410922,4.434842973
+43.72968433,-1.111335109,-4.067013598,-1.142120846,4.368077993
+43.73972533,-1.496116398,-4.44113015,-0.3805397183,4.701788145
+43.74976533,-0.8514666463,-4.266946273,-0.7389260906,4.413370335
+43.75980633,-1.281930988,-3.727439472,-0.6412033296,3.993531493
+43.76984633,-1.232665419,-4.28233059,-0.8286422592,4.532600502
+43.77988733,-0.8740431844,-3.733741894,-0.8798527586,3.934325977
+43.78992733,-1.191656191,-4.199098106,-1.569812511,4.638618405
+43.79996833,-2.044485239,-4.617380432,-0.3955635542,5.065233704
+43.81000933,-0.9809724596,-4.236064496,-0.522418313,4.37943721
+43.82004933,-1.880351995,-3.992153158,-0.3373527682,4.425699645
+43.83009033,-1.463919874,-4.378902034,-0.5043638653,4.644591191
+43.84013033,-1.676030546,-4.88096999,0.5207775843,5.186921604
+43.85017133,-0.5069541087,-3.403844033,0.21659724,3.44819823
+43.86021133,-2.031488486,-3.016887873,-3.926388938,5.352110612
+43.87025233,-2.340570844,-4.694559586,1.25783432,5.394377513
+43.88029233,-1.470585408,-5.226101017,0.8200912911,5.490655972
+43.89033333,-2.073216556,-3.455751813,0.5229305291,4.063730284
+43.90037333,-1.300143457,-3.603710927,-1.92812287,4.288911664
+43.91041433,-1.809571596,-5.3219515,2.731203441,6.249575134
+43.92045433,-1.752268736,-4.474519213,-0.5317674261,4.834722795
+43.93049533,-2.079180277,-2.999813126,-0.2869380748,3.661175068
+43.94053633,-1.118923699,-4.18885817,-0.09517162085,4.336770763
+43.95057633,-3.218137634,-4.961399319,0.5776733315,5.941851522
+43.96061733,-1.239776803,-3.604121402,0.1273693138,3.813523376
+43.97065733,-2.175499122,-3.133898259,0.157296533,3.818226935
+43.98069833,-1.224278173,-4.034019222,-0.2315403843,4.22205863
+43.99073833,-2.269845262,-4.77193579,0.7485722423,5.337033736
+44.00077933,-1.677655779,-4.253437743,-0.6816648924,4.622870166
+44.01081933,-2.232319294,-3.738389261,-0.3650761718,4.369448971
+44.02086033,-1.487248218,-3.859374,-0.03917459071,4.136207149
+44.03090033,-1.623792398,-4.185258332,0.1221196836,4.490879899
+44.04094133,-1.631939616,-4.233008741,-0.6905906671,4.588954716
+44.05098233,-2.334227638,-4.525428873,-0.4248329616,5.109658325
+44.06102233,-1.837697726,-4.329472304,-0.2824380577,4.711818611
+44.07106333,-1.851150123,-4.571018736,-0.3671379,4.945276464
+44.08110333,-1.709068922,-4.356166598,-0.6547834879,4.725023325
+44.09114433,-1.886815799,-4.255926026,-0.3278142053,4.666952148
+44.10118433,-1.694987804,-4.324001357,-0.9726276058,4.745100194
+44.11122533,-1.611846098,-4.569790529,-0.4413232791,4.865778412
+44.12126542,-2.154034432,-4.702828133,-1.0725267,5.282685899
+44.13130642,-1.602417609,-4.632403683,-0.9142858422,4.986263599
+44.14134642,-1.995527233,-4.303898922,-0.7785094017,4.807468331
+44.15138742,-2.000889714,-4.826721278,-0.5320896077,5.252039346
+44.16142742,-1.909718174,-4.995115533,-0.2645268667,5.354267192
+44.17146842,-2.464864815,-4.780492314,-0.5701526427,5.408672605
+44.18150942,-2.413053514,-4.586953276,-0.6276711184,5.220817814
+44.19154942,-2.110887243,-4.919233877,0.1728583127,5.355799369
+44.20159042,-1.733367027,-5.136441566,0.3278826177,5.430939166
+44.21163042,-3.153476199,-4.961926153,-0.0538592881,5.879457807
+44.22167142,-2.09126808,-5.120852889,0.1403939867,5.533195006
+44.23171142,-2.750950658,-4.874311766,-0.1668386042,5.599507106
+44.24175242,-2.452114084,-5.193829064,0.2935284716,5.751076664
+44.25179242,-1.758417376,-4.589211178,0.4373541892,4.93398111
+44.26183342,-2.350755524,-4.465346393,-0.6064597589,5.082633509
+44.27187342,-2.5064239,-4.789105847,-0.24697411,5.41097882
+44.28191442,-2.033359011,-4.915712684,0.2451351607,5.325304808
+44.29195442,-1.92227887,-4.598236063,-0.2499374789,4.990130228
+44.30199542,-3.599924563,-4.312722078,-0.6815777689,5.658937783
+44.31203642,-1.757639404,-4.023913771,-0.05009660482,4.391319617
+44.32207642,-1.912586233,-4.269176986,-0.8432334012,4.753409387
+44.33211742,-2.487446761,-4.504227454,-1.57982236,5.382498958
+44.34215742,-2.497950115,-5.707339144,0.5674395347,6.255834278
+44.35219842,-1.859688227,-4.366068565,-0.919296906,4.833849586
+44.36223842,-2.805727666,-3.456221929,-1.177135727,4.604696112
+44.37227942,-2.365004896,-4.54728635,-1.77007497,5.422566432
+44.38231942,-2.196175315,-5.078102142,-0.4764896035,5.553138727
+44.39236042,-2.577869858,-4.439323068,-0.4079491264,5.149701428
+44.40240042,-2.154688443,-4.699671514,-1.387441363,5.352998054
+44.41244142,-2.87234821,-4.746692776,0.1922026563,5.551433906
+44.42248142,-2.127603848,-3.919589796,0.1557084292,4.462524781
+44.43252242,-2.9493461,-4.706202854,-1.791685694,5.835848297
+44.44256342,-2.873720844,-5.637592971,1.457751208,6.49351712
+44.45260342,-1.804659496,-4.495185904,1.450971361,5.056561094
+44.46264442,-3.564186966,-4.802886565,-0.341809516,5.990657879
+44.47268442,-2.417396241,-5.105567683,0.3379333967,5.659048059
+44.48272542,-2.081836814,-5.056456919,2.066194927,5.845593432
+44.49276542,-3.115357616,-4.889769173,-0.7149560148,5.841785492
+44.50280642,-2.203880776,-4.976091033,-0.2295657796,5.447134374
+44.51284642,-1.441245103,-4.829887545,0.0212575525,5.04038223
+44.52288742,-2.150257569,-5.047809471,-0.4299551225,5.503530638
+44.53292742,-1.818118763,-5.088096203,-1.099094694,5.513826979
+44.54296842,-1.771671113,-4.731033055,-0.866474914,5.125648357
+44.55300842,-1.502129528,-3.595527164,-1.292165077,4.105350082
+44.56304942,-1.453387139,-3.527826347,-2.258133289,4.433628183
+44.57309042,-1.934439471,-4.496198642,-2.615050841,5.549445846
+44.58313042,-2.631210206,-4.671799591,-0.8091423798,5.42251694
+44.59317142,-1.852316058,-3.799689423,-1.330800555,4.431675147
+44.60321142,-2.842905433,-4.00045942,-1.204621734,5.053404832
+44.61325242,-2.161720304,-4.070788268,-0.09867059469,4.610215579
+44.62329242,-2.583178838,-3.988293411,-0.1969944495,4.755849456
+44.63333342,-2.467748661,-3.927421264,-0.6826647663,4.688331518
+44.64337342,-3.122273702,-4.686728702,0.06615890622,5.631908735
+44.65341442,-2.340955298,-4.164694551,0.9071610099,4.86288942
+44.66345442,-2.947320917,-4.118338703,-0.5326018238,5.092256765
+44.67349542,-2.601449925,-4.620549623,0.0648298341,5.302944789
+44.68353542,-2.098389404,-4.630200453,1.144302442,5.210702678
+44.69357642,-2.091912443,-4.630740735,0.3656796044,5.094465526
+44.70361742,-1.927777445,-4.414310726,-0.6484515381,4.860345097
+44.71365742,-2.212573247,-3.990060439,0.5187445074,4.591857853
+44.72369842,-2.085956762,-4.17300783,-0.5857179308,4.701943796
+44.73373842,-2.157733088,-4.2461258,-0.1043558425,4.764061978
+44.74377942,-1.268219706,-4.561697982,0.4609699237,4.757096065
+44.75381942,-2.699118599,-4.169451846,-0.04640525758,4.967063857
+44.76386042,-1.609810098,-3.328787419,-0.1423452026,3.700348144
+44.77390042,-2.400824062,-3.460938586,-0.7542931581,4.279136623
+44.78394142,-2.410212498,-4.236579051,0.5567128175,4.905879687
+44.79398142,-1.863020117,-4.274194189,-0.5210348618,4.691594319
+44.80402242,-2.495436982,-3.661177655,-1.047543887,4.552886529
+44.81406242,-1.784036805,-2.815152209,-0.9892003691,3.476548094
+44.82410342,-1.960927358,-3.531687849,-1.4921036,4.306324223
+44.83414342,-2.467023022,-4.385543302,-1.962043152,5.400815306
+44.84418442,-1.609900583,-3.87888762,-0.1632074833,4.202878269
+44.85422542,-1.824730064,-3.839299924,-1.773873906,4.606136379
+44.86426542,-2.606610678,-3.923025035,-2.061128315,5.141283359
+44.87430642,-1.394010564,-4.746854451,0.1302777189,4.949026664
+44.88434642,-1.949961051,-4.491438131,-0.9717774206,4.991965138
+44.89438742,-2.198855094,-4.520556096,-0.4525815082,5.047298402
+44.90442742,-1.376996043,-4.700139876,0.08916068316,4.8985082
+44.91446842,-1.95898155,-4.549190788,-0.1042102468,4.954150312
+44.92450842,-2.139402359,-4.70799064,-0.6391942263,5.210641763
+44.93454942,-2.157079662,-4.855164181,0.9274116719,5.393116381
+44.94458942,-1.970511967,-4.549127346,0.9280542809,5.043685336
+44.95463042,-2.184987984,-4.302304386,0.8768589842,4.904373273
+44.96467042,-2.22272986,-4.196809506,0.2930221027,4.75810887
+44.97471142,-2.448440863,-4.136113361,0.5348331213,4.836149591
+44.98475242,-1.291715719,-3.709617451,0.4843634641,3.957827573
+44.99479242,-3.085062607,-4.268132673,-0.2285723376,5.271319865
+45.00483342,-2.203859726,-4.227810274,1.31898684,4.946827639
+45.01487342,-1.788185843,-3.163246019,-0.02335845709,3.633769339
+45.02491442,-2.58524349,-3.237001044,-1.112388339,4.289413418
+45.03495442,-1.887486767,-3.689090216,-0.3883223623,4.162065254
+45.04499542,-1.416803157,-3.53546018,0.731339913,3.878358923
+45.05503542,-2.160906811,-3.153654832,-2.512034011,4.574425856
+45.06507642,-2.199162219,-3.189181929,-0.8843866897,3.973579704
+45.07511642,-0.9015212973,-3.550538102,-0.7531190372,3.739819481
+45.08515742,-1.821099381,-2.927521368,-1.148841636,3.634091553
+45.09519742,-1.0429164,-2.819688186,-2.069185193,3.649636071
+45.10523842,-1.724498701,-3.541827505,-0.4070030469,3.960314296
+45.11527842,-1.023310833,-3.131702338,-0.5951284397,3.3479699
+45.12531992,-1.804385846,-3.224595883,-1.340194691,3.930642276
+45.13536092,-1.572736704,-3.622084633,0.1597634733,3.952027606
+45.14540092,-1.17290629,-3.448353331,1.037938666,3.787369342
+45.15544192,-1.694296516,-2.903668821,1.193536583,3.567416836
+45.16548192,-1.647868162,-2.848805858,0.06143026292,3.291646697
+45.17552292,-1.315123293,-3.741941444,1.071708675,4.108556259
+45.18556292,-1.970255567,-2.807073403,0.9084555835,3.547796448
+45.19560392,-0.9763712856,-3.021139091,-1.58619524,3.549168583
+45.20564392,-1.71336224,-3.584360737,1.282310765,4.174634469
+45.21568492,-1.319626087,-4.261640802,1.463279166,4.695123135
+45.22572492,-2.35590809,-3.280454627,0.765916838,4.110755903
+45.23576592,-0.7910779186,-2.067034295,0.08697557867,2.214949164
+45.24580592,-0.5777910067,-3.803028768,0.2169147438,3.852781108
+45.25584692,-1.34715741,-5.263373508,1.275818017,5.580828378
+45.26588692,-0.3699334903,-4.059290011,0.1834201384,4.080236406
+45.27592792,-0.8983765917,-2.991290224,-1.906042614,3.658947411
+45.28596892,-0.3150499893,-3.277813732,-1.087569247,3.46787056
+45.29600892,-0.4655309712,-4.117344091,0.4956392348,4.173116306
+45.30604992,-0.757759022,-3.817074949,-1.01514388,4.021787787
+45.31608992,-0.4722368505,-3.270128444,-1.583082182,3.663727184
+45.32613092,-0.4519918896,-3.464619408,-0.8171951652,3.588271485
+45.33617092,-0.5309379986,-3.778768378,-1.355090473,4.049352517
+45.34621192,-0.2187361697,-4.137979792,-0.9426267117,4.249619676
+45.35625192,-0.1153356527,-4.202864298,-1.155498106,4.360337887
+45.36629292,-0.1383828003,-3.829025781,-0.1112391847,3.833140017
+45.37633292,-0.3124447989,-3.282682123,-0.09609314203,3.298917636
+45.38637392,-0.7242672671,-3.190419785,-0.2862790936,3.284097623
+45.39641392,-0.1473471484,-3.340363736,-0.9576803684,3.478058763
+45.40645492,0.04286122363,-4.294650381,1.176017155,4.452962534
+45.41649492,-0.03450624682,-3.918306332,1.450174386,4.178195896
+45.42653592,-0.2974692391,-4.252975228,0.777628811,4.333704283
+45.43657692,-1.065094378,-4.543561966,0.7354241931,4.724323244
+45.44661692,-0.3055026739,-4.180438179,2.046398594,4.664455216
+45.45665792,-0.07499377498,-4.063760499,0.3617216241,4.080516633
+45.46669792,-0.6696130501,-4.290007984,1.224122198,4.511211068
+45.47673892,0.4864649534,-4.476490602,1.387802137,4.711858553
+45.48677892,-0.9851625744,-3.603143455,0.7068962127,3.801695715
+45.49681992,-0.8370936786,-2.861691075,-0.1341146618,2.984625333
+45.50685992,0.01561431332,-2.754991668,0.4380371439,2.789641454
+45.51690092,-0.4319181059,-3.959119313,0.8485309786,4.071999976
+45.52694092,-0.5737247068,-3.936281843,0.1100750041,3.979395845
+45.53698192,-0.1976659474,-3.021173297,-0.5297477978,3.07362858
+45.54702192,-0.5935567081,-2.256501039,-1.172076132,2.611104931
+45.55706292,0.4076296491,-2.808168586,-0.7219235569,2.927993573
+45.56710292,0.2603157385,-3.27940739,-0.2113014168,3.296501995
+45.57714392,0.1003439216,-2.326493526,-1.681600165,2.87235446
+45.58718492,0.002895559464,-2.26116127,-2.478070459,3.354652273
+45.59722492,0.2219866004,-2.583469152,-1.216038423,2.863972827
+45.60726592,-0.09805530315,-2.438221684,-0.7197618413,2.544129897
+45.61730592,-0.5570776107,-2.75486683,-1.941920545,3.416238007
+45.62734692,0.4163020932,-2.657005783,-1.250469167,2.965916435
+45.63738692,0.267630989,-3.738995032,-1.164707471,3.925334851
+45.64742792,-0.127041888,-3.224380413,-0.1418499434,3.229998467
+45.65746792,0.5991344402,-3.148358424,-1.097377367,3.387530063
+45.66750892,-0.04391657297,-4.03567603,-0.3158981645,4.04825905
+45.67754892,0.4683518873,-4.306747685,0.8216332018,4.409366194
+45.68758992,0.3268479529,-4.606641144,0.006532509327,4.618226379
+45.69762992,-0.2592038905,-4.296941612,0.2427202606,4.311589846
+45.70767092,0.8380692865,-4.26208139,1.352120672,4.549277768
+45.71771092,0.1582963703,-4.542115072,0.5752484912,4.581132818
+45.72775192,0.1428213852,-4.073488512,1.287115422,4.274385654
+45.73779192,0.1802533046,-4.79018115,-0.2622429442,4.800739325
+45.74783292,-0.5419028436,-4.350846801,1.758332006,4.723902838
+45.75787392,0.5503375983,-3.733392523,-0.3351781887,3.788592828
+45.76791392,-0.6327886746,-3.714225934,0.00954441011,3.767756215
+45.77795492,0.1742594518,-3.545520899,-0.5818149143,3.597164633
+45.78799492,-0.03414163638,-3.473254284,-0.7552111709,3.554575204
+45.79803592,-0.2154554615,-3.810198039,-1.934529664,4.278602012
+45.80807592,-0.02784750159,-3.732887031,-1.07337864,3.884245457
+45.81811692,-0.1524435541,-3.591821199,-0.7229590988,3.667027191
+45.82815692,0.6103322236,-3.380363662,-0.9659337133,3.568247728
+45.83819792,0.08407383394,-4.16648263,-0.2078796262,4.172512415
+45.84823792,-0.5719902033,-4.011391959,-0.179653362,4.055947925
+45.85827892,-0.5922815035,-3.668156015,-0.6322734618,3.769076234
+45.86831892,-0.7474449722,-4.14941987,-0.2536469525,4.223824809
+45.87835992,0.1458693194,-4.44922065,0.9107184559,4.543814516
+45.88839992,-0.4192525982,-4.191765113,0.7448282701,4.278017842
+45.89844092,-0.3274553324,-4.473868418,-0.598554908,4.525593176
+45.90848192,-0.001543765431,-4.71409718,0.8606990343,4.792026443
+45.91852192,-0.5744762933,-4.993360199,0.5076576018,5.051869489
+45.92856292,-1.025401651,-4.647358522,0.0971930033,4.760129857
+45.93860292,-0.3906487136,-4.534490303,0.7356551582,4.610357604
+45.94864392,-0.3933600675,-4.83337921,1.08289089,4.968796575
+45.95868392,-0.4082131647,-5.373097095,0.9158131349,5.465850719
+45.96872492,-0.2931197878,-5.130639959,-0.2579861712,5.145477865
+45.97876492,-0.8189000671,-4.456775837,0.2917684597,4.540768329
+45.98880592,-0.4544639827,-4.879067599,-0.3473708028,4.912484567
+45.99884592,-0.6007386969,-5.99949469,1.184638875,6.144769546
+46.00888692,0.3576316795,-5.620620843,1.017440082,5.723151527
+46.01892692,-0.5284911216,-3.90814124,-1.369630744,4.174776544
+46.02896792,-0.4368204845,-3.639540326,-1.533355706,3.973442543
+46.03900792,-0.02180035684,-4.085380579,-0.920781514,4.187916944
+46.04904892,0.008786738869,-4.395772128,-0.528510527,4.427438671
+46.05908892,-0.5843670047,-4.435869994,-1.099863018,4.607399056
+46.06912992,-0.6508154943,-3.53965468,-1.452731373,3.881126705
+46.07917092,-0.07454298207,-3.022730118,-2.262459644,3.776397445
+46.08921092,-0.1900983164,-3.163080836,-2.324541287,3.929975819
+46.09925192,-0.4197795054,-4.307317497,-0.7249366271,4.388021418
+46.10929192,0.5101768747,-3.569229604,-0.4518769187,3.633713412
+46.11933292,-0.5291593852,-3.875222001,-1.407246467,4.156645021
+46.12937242,-0.9801119687,-4.604448145,-0.2451111871,4.713983633
+46.13941342,-0.190545665,-4.001437951,0.9052583259,4.106982586
+46.14945342,-0.4058738764,-3.453081097,-0.1303116328,3.479293576
+46.15949442,-0.6589144727,-4.408305928,0.8049300456,4.529375433
+46.16953442,-0.321016744,-5.4750433,1.783605427,5.767182952
+46.17957542,-1.031983934,-4.411585338,0.9695057774,4.633251287
+46.18961542,-0.3610471113,-3.311966441,-0.3866752017,3.353952062
+46.19965642,-0.7392422788,-4.090819952,-0.2686491537,4.165748359
+46.20969642,-0.5437873646,-4.605681615,1.001167281,4.744506694
+46.21973742,-0.4890573165,-4.419131755,-0.522063387,4.47665642
+46.22977742,-0.6768626473,-3.728186747,-0.7168972903,3.856353353
+46.23981842,-0.5143355972,-3.99308345,0.3362061292,4.040085532
+46.24985942,-0.7052972185,-3.959128668,-0.4320244521,4.044599993
+46.25989942,-0.4141522182,-3.164366931,-0.432350142,3.220507224
+46.26994042,-0.3878314155,-3.309959969,-2.091071906,3.934314416
+46.27998042,-0.4234475734,-3.963161493,-0.4582258254,4.011973052
+46.29002142,-0.6082819705,-3.943420123,-0.2780707723,3.999736564
+46.30006142,-0.2792364147,-3.54464294,-1.579047019,3.890482751
+46.31010242,-0.3330716562,-3.146955092,-0.1018497258,3.166170628
+46.32014242,-0.03888393841,-3.598976437,-0.4424798584,3.626283466
+46.33018342,0.0426544606,-3.885184779,0.3690663117,3.902907905
+46.34022342,-0.6437986162,-3.674763953,-0.704262042,3.796623736
+46.35026442,-0.01636340559,-3.536437542,-1.284512826,3.762529927
+46.36030442,-0.06913032417,-2.658293924,-0.0957885021,2.660917328
+46.37034542,0.02003790555,-2.616411488,-1.464411771,2.998418321
+46.38038542,0.2310124355,-4.024938788,0.4259895408,4.054006177
+46.39042642,-1.272654381,-5.129036652,0.73644921,5.335637131
+46.40046642,0.0438977431,-3.938992904,0.3855519515,3.958060436
+46.41050742,-0.3749137101,-2.532555399,0.1001680666,2.562114514
+46.42054842,-0.03390140718,-3.312701436,0.5290724444,3.354855848
+46.43058842,0.7542661878,-4.069968781,1.794831496,4.511649749
+46.44062942,-0.7533415968,-3.681991696,0.1114023221,3.759919798
+46.45066942,-0.5582391601,-3.649089706,0.4584398335,3.719899693
+46.46071042,0.268460179,-2.746059754,0.5521730393,2.813860357
+46.47075042,-0.3392031196,-2.412660873,-0.39161376,2.467661359
+46.48079142,-0.3310229745,-3.275514607,-0.2479763228,3.301524558
+46.49083142,0.3082834087,-2.247309216,0.1656679916,2.274397339
+46.50087242,-0.6414399225,-2.264756577,-1.008140085,2.560647175
+46.51091242,-0.7772215524,-2.881525123,0.747493431,3.076687635
+46.52095342,0.5606816152,-1.982053494,0.4650904566,2.111683939
+46.53099342,-0.8876546254,-2.092410334,-1.387446041,2.662915368
+46.54103442,0.1569765624,-2.34305518,0.9538504422,2.534636045
+46.55107442,-0.07858265891,-2.493417938,-0.3611105901,2.520656483
+46.56111542,-0.7176827907,-1.682284143,-0.9873795462,2.078477061
+46.57115542,-0.03163801395,-1.343585199,-0.163126207,1.353821374
+46.58119642,0.2955636498,-1.642005744,-0.1380211866,1.674093959
+46.59123742,-0.4099350601,-2.074631144,-0.931141026,2.31066327
+46.60127742,0.01103056219,-1.967014601,-0.2822866148,1.987197486
+46.61131842,0.302793531,-1.665218898,-0.09146974862,1.694993987
+46.62135842,-0.4095959947,-1.225128285,-0.8275652021,1.534135703
+46.63139942,0.04625968932,-1.726384282,0.009108792543,1.727027972
+46.64143942,-0.06911814552,-2.093741452,0.5111273396,2.156335258
+46.65148042,0.3044583064,-1.437637809,-0.3355705369,1.507350297
+46.66152042,-0.04177437242,-1.512143177,-0.6310268354,1.639059777
+46.67156142,0.1996156649,-1.73521387,-0.07656402647,1.748335105
+46.68160142,0.4345765425,-1.638544192,-0.2548041165,1.714237142
+46.69164242,0.3269540799,-1.535984468,-0.3446161795,1.607764774
+46.70168242,0.05059607581,-1.682165883,0.071947065,1.684463832
+46.71172342,0.2436821641,-2.027813073,-0.3636892122,2.074530476
+46.72176342,0.09422344001,-1.643323414,-0.08667854011,1.648303088
+46.73180442,0.5497220327,-1.345349451,-0.2722136164,1.478600592
+46.74184442,0.1094636868,-1.663114485,0.04985043705,1.667458292
+46.75188542,0.2257025973,-1.795148854,0.8397145468,1.994648237
+46.76192642,-0.0127022172,-1.405287504,0.2708336735,1.431204106
+46.77196642,-0.02893781545,-1.11894526,0.2938021213,1.157236181
+46.78200742,0.02730877203,-1.307519866,1.032308967,1.666137981
+46.79204742,-0.1036635139,-1.141221983,0.727977764,1.3576028
+46.80208842,0.2483386309,-0.6436208609,0.08235978663,0.694768323
+46.81212842,0.1091669863,-0.6619090511,-0.0980472815,0.6779780913
+46.82216942,-0.03525759576,-1.017695824,0.2832040429,1.056954313
+46.83220942,0.2655591926,-0.770073916,0.1499997926,0.8282725751
+46.84225042,0.05968784748,-0.7185690093,-0.4873396969,0.8702896302
+46.85229042,0.1419799526,-1.077466721,-0.1361202568,1.09527237
+46.86233142,0.6193990624,-0.7663547214,0.2525377357,1.017216823
+46.87237142,0.4131284804,0.0014045012,-0.9411520439,1.027834755
+46.88241242,0.5980168911,-0.1943927492,-0.713670212,0.9511771205
+46.89245242,0.5696483935,-0.6603796387,0.1244264102,0.8809554421
+46.90249342,0.3712420607,-0.1786231923,-1.170695019,1.241069595
+46.91253342,0.3334611538,-0.5699889938,-0.7646029687,1.010297725
+46.92257442,0.8315153617,-0.8337434433,-0.06120865345,1.179106622
+46.93261542,0.8287893898,-0.6386604486,-0.7699712974,1.299089997
+46.94265542,0.331453293,-0.747572076,-0.7064752132,1.080663001
+46.95269642,1.314718227,-0.8418200561,-0.1629022586,1.569612108
+46.96273642,0.690586501,-0.9019115259,-1.301370349,1.727402356
+46.97277742,0.4894984524,-1.070913015,-0.9246780986,1.49716165
+46.98281742,1.350388142,-1.27744939,-0.3419925338,1.890075123
+46.99285842,0.4947511524,-1.145298735,-0.839745537,1.503881798
+47.00289842,0.959245595,-0.9223988539,-0.6944194239,1.501062988
+47.01293942,0.9402081572,-1.433841212,-0.3181025648,1.743869617
+47.02297942,0.8256855416,-1.338547531,-0.977770232,1.851891123
+47.03302042,0.9586141688,-1.056012482,-0.5448423851,1.526747102
+47.04306042,0.8655158244,-1.121385961,-1.009885479,1.739681809
+47.05310142,0.6955681095,-1.61871336,-0.7805085647,1.926977311
+47.06314142,0.439682185,-1.626395871,-0.09576335907,1.687499503
+47.07318242,0.7560866453,-0.9336104514,0.07105945766,1.203472034
+47.08322242,0.6741923701,-1.113152862,-0.6231313401,1.442891997
+47.09326342,0.315745004,-1.899807143,0.5750719053,2.009892979
+47.10330342,0.7431315543,-1.770165017,0.4448035419,1.970679803
+47.11334442,0.3328832296,-1.200921251,-0.5000936437,1.342801827
+47.12338542,0.4845352261,-1.169702966,0.3156484884,1.304842283
+47.13342542,0.6692554928,-1.886583519,0.8586764824,2.178170239
+47.14346642,0.4084858642,-1.714404068,-0.08828243136,1.764606414
+47.15350642,0.4819117997,-1.650826269,0.003893076181,1.719732976
+47.16354742,0.6205951104,-2.293968389,0.4734087056,2.423127125
+47.17358742,0.5655426979,-2.192263966,0.8200287259,2.40796739
+47.18362842,0.5321122291,-1.903606664,0.05883409917,1.977453718
+47.19366842,0.3147384058,-1.624401239,0.4811053956,1.72313727
+47.20370942,0.7168087781,-1.843183584,-0.1050966847,1.980450924
+47.21374942,-0.03340610233,-2.326735747,0.5567940938,2.392662715
+47.22379042,0.7600051568,-2.346671829,1.068855819,2.688294863
+47.23383042,0.3832968266,-1.893795328,0.285371021,1.953154838
+47.24387142,0.300506356,-1.928692681,-0.09558034122,1.954301699
+47.25391142,0.6128483902,-2.211518701,-0.1807491302,2.301970539
+47.26395242,0.8916248117,-2.208851932,-0.2647315192,2.396686137
+47.27399242,0.8983991765,-2.416111023,-1.141187046,2.819046191
+47.28403342,0.2438413546,-2.758233365,-0.2509911472,2.780342867
+47.29407342,0.6245105521,-2.080879771,0.1479468352,2.17760472
+47.30411442,0.5611993861,-1.698894767,-0.7903201926,1.955963749
+47.31415542,0.3294709408,-2.601389406,0.1869781691,2.628828404
+47.32419542,0.7220725147,-2.820936567,1.194562184,3.147387908
+47.33423642,0.29201386,-2.138578341,-0.2335991889,2.171026945
+47.34427642,0.2140197873,-1.917823292,-0.5620425546,2.009911063
+47.35431742,0.6250183097,-2.462367469,0.3718431544,2.567521912
+47.36435742,0.2326694085,-2.58685966,-0.07139801145,2.598283208
+47.37439842,0.003275811207,-2.124972601,-0.508060475,2.184867211
+47.38443842,0.5833989982,-1.83764554,-0.1524310648,1.934045178
+47.39447942,0.359020649,-1.999602304,0.2599058121,2.048134817
+47.40451942,-0.07032303739,-2.210552303,0.6506921911,2.3054039
+47.41456042,0.06622309769,-2.420844929,0.7389711142,2.531986172
+47.42460042,-0.2623123251,-2.32479988,1.108492924,2.58887211
+47.43464142,0.05059940142,-1.893952034,0.6451145321,2.001446318
+47.44468142,0.07801193411,-2.143341921,1.107871365,2.413996564
+47.45472242,-0.01490120882,-2.220294787,0.5858430612,2.296332528
+47.46476242,-0.03667146164,-2.141362492,0.4492579508,2.188289475
+47.47480342,0.1040527374,-2.036359071,0.2152073568,2.050341299
+47.48484442,0.8442263315,-2.458340199,0.1706468958,2.604856041
+47.49488442,0.3639433103,-2.714430703,0.2448006999,2.749639278
+47.50492542,0.5918871818,-2.485840239,-0.3685453248,2.581774155
+47.51496542,0.7469311481,-2.419925162,-1.144324661,2.779104687
+47.52500642,0.5378789725,-2.584416693,-0.6125987506,2.709944771
+47.53504642,0.7712318109,-2.422297377,-0.6569773632,2.625631799
+47.54508742,0.2419724017,-1.94544013,-1.073166971,2.234944135
+47.55512742,0.212650479,-2.333287698,-0.9804546887,2.539831314
+47.56516842,0.5623368157,-2.737193329,0.2840536433,2.808760667
+47.57520842,0.658629494,-2.589405245,-0.2411292332,2.682714231
+47.58524942,0.2052559074,-2.238509156,-0.6665135872,2.344630801
+47.59528942,0.857776669,-2.491745342,-0.09780520678,2.637070633
+47.60533042,0.790502041,-2.869350343,0.4032719386,3.003446874
+47.61537042,0.8076954862,-2.110375027,-0.537301231,2.322659546
+47.62541142,0.245435269,-2.218949782,-0.580192312,2.306642522
+47.63545142,0.004417452654,-1.997586915,0.1632677096,2.004252813
+47.64549242,0.637996278,-1.951244807,-0.9628469682,2.267480944
+47.65553242,-0.3064795244,-2.165892293,-0.8185926497,2.335618344
+47.66557342,0.6924954707,-2.445384523,0.9351177174,2.708117536
+47.67561342,0.5325579697,-2.416203555,0.8726910889,2.623594356
+47.68565442,0.01276253488,-2.157786298,-0.1949262893,2.166610451
+47.69569542,0.2746982079,-2.226582298,0.9087976456,2.420545599
+47.70573542,0.5629077598,-2.93965551,1.103276038,3.18993067
+47.71577642,-0.2104788962,-3.389088877,0.6586900127,3.458915627
+47.72581642,0.1620526582,-2.831456877,1.100676366,3.042186315
+47.73585742,0.5185671906,-2.519829519,0.8248462468,2.701633592
+47.74589742,-0.4472737347,-3.057641796,0.7937033916,3.190484638
+47.75593842,0.6046648829,-2.960348513,1.021099854,3.189345992
+47.76597842,0.003521293765,-2.670031625,0.4524376667,2.708095478
+47.77601942,0.3415252682,-2.558113579,-0.4540678704,2.620450767
+47.78605942,0.1830756643,-2.959736602,-0.3140790957,2.981979734
+47.79610042,0.01864140315,-2.528613206,0.2860984147,2.544815229
+47.80614042,0.3703672807,-2.365505856,-0.1361068082,2.39818993
+47.81618142,-0.04987174741,-2.032981134,-0.06700792193,2.034696426
+47.82622142,0.446797077,-2.468044823,-0.4411192113,2.546656442
+47.83626242,-0.1113525294,-2.964048631,0.3126552987,2.982572214
+47.84630242,0.6568610767,-2.61620245,0.4256445551,2.730779197
+47.85634342,-0.2480724546,-2.099177755,0.4522341835,2.161620445
+47.86638342,-0.467322083,-1.981232545,0.1204216522,2.039160048
+47.87642442,0.05811791576,-2.179872401,0.963569684,2.384048639
+47.88646542,-0.08782207277,-2.579005095,0.1369435447,2.584131098
+47.89650542,0.02427842511,-2.177201539,-0.09603466988,2.179453748
+47.90654642,0.4256513159,-2.109569573,0.334570663,2.177934883
+47.91658642,-0.129009202,-2.128041658,-0.2140753359,2.142669578
+47.92662742,0.04369387628,-2.187660015,-0.1081436688,2.190767114
+47.93666742,0.01722765833,-2.432122746,0.1389561564,2.436149966
+47.94670842,0.3408984832,-2.526568435,-0.1823085827,2.555972662
+47.95674842,0.237106897,-2.141873685,-0.6791447425,2.259442441
+47.96678942,0.284128104,-2.506492605,-0.8041728312,2.647626843
+47.97682942,0.1747497774,-2.900471563,-0.1810368133,2.911365161
+47.98687042,0.5175378614,-2.505401222,-0.1250573248,2.561351217
+47.99691042,0.1807308212,-1.98897572,-0.9350463814,2.205221028
+48.00695142,0.1965508834,-2.410026556,-0.8547056383,2.564640712
+48.01699142,0.0719764701,-2.497189977,-0.3566731381,2.523559811
+48.02703242,0.1043422751,-2.602484882,-0.5848051804,2.669421655
+48.03707242,0.5553543266,-2.415580096,-0.7381174207,2.586167619
+48.04711342,0.2267442057,-2.341118728,0.3603036743,2.379510154
+48.05715342,-0.6321677734,-2.353674454,-0.4415700316,2.476772824
+48.06719442,0.3889752039,-1.834081808,-0.3275282764,1.903268914
+48.07723542,0.8057993804,-2.828706931,-0.1504968059,2.945088256
+48.08727542,-0.561535601,-3.703823738,0.476818217,3.77637235
+48.09731642,0.9311492852,-2.325351857,0.4031859845,2.537096606
+48.10735642,0.0009561613714,-1.753018057,-1.574125417,2.356044153
+48.11739742,0.00139944884,-2.594763926,-0.3542570686,2.618835593
+48.12743792,0.5834149318,-3.117981846,1.613828012,3.559020178
+48.13747892,-0.4178087379,-2.497089405,-0.4312514502,2.568267402
+48.14751892,-0.212798779,-2.193638793,-0.2876736546,2.22263146
+48.15755992,0.5092378484,-3.162573882,1.191748504,3.417815273
+48.16759992,-0.2091755519,-3.40370867,1.308254861,3.652467372
+48.17764092,0.4834262651,-2.53646894,0.05135784924,2.582636883
+48.18768092,0.3189736903,-2.283815722,-0.3583126974,2.333655171
+48.19772192,-0.2466547059,-2.793399689,-0.1261367208,2.807103639
+48.20776192,0.4436215638,-3.023363079,0.02927466989,3.055876537
+48.21780292,0.085162686,-2.91594505,-0.7428998584,3.010297065
+48.22784292,0.1399367527,-2.419980125,-0.7603327471,2.54047082
+48.23788392,0.8081291304,-1.881429637,0.1756222916,2.055162611
+48.24792392,-0.3060375662,-2.44001868,-0.1752995253,2.465376254
+48.25796492,-0.4287118582,-2.791196751,0.5148613715,2.870479993
+48.26800592,0.7453373433,-2.799243981,0.5612461638,2.950642621
+48.27804592,-0.5199276915,-2.534975854,-0.3843906945,2.616139062
+48.28808692,0.04404976614,-2.140977746,0.06205766916,2.142329863
+48.29812692,0.3156277673,-2.378856073,0.4559781557,2.442640617
+48.30816792,-0.3569518311,-2.707019649,0.3481496519,2.752558478
+48.31820792,0.1418120735,-2.542540981,-0.3127903694,2.565631135
+48.32824892,-0.08164046033,-2.1026472,0.02650425911,2.104398463
+48.33828892,-0.04755259093,-2.519688893,-0.6640922552,2.606168047
+48.34832992,-0.03939823757,-2.400716327,-0.07227977157,2.40212728
+48.35836992,0.3237678224,-2.393328955,-0.5195777357,2.470386632
+48.36841092,-0.3608461863,-2.419182273,-0.7676826972,2.563589195
+48.37845092,0.5515561581,-2.273479599,0.01723057508,2.339491521
+48.38849192,-0.4040755287,-3.070822298,-0.7294536012,3.182032239
+48.39853192,-0.09314945268,-2.43021553,-0.5525525236,2.49398048
+48.40857292,0.894626553,-2.05598335,-1.442750176,2.666261854
+48.41861292,-0.7307741218,-2.5437841,-1.18769346,2.900945383
+48.42865392,0.4834776109,-2.441424643,0.1397449458,2.492756213
+48.43869392,-0.06734547073,-2.848144538,-0.3027395904,2.864980625
+48.44873492,-0.4926838327,-2.542993556,-0.7205594015,2.688635237
+48.45877492,0.4162514051,-2.279911829,-0.2035567796,2.326520694
+48.46881592,-0.3537415635,-2.778229965,0.05340145111,2.801168783
+48.47885692,-0.05154037373,-2.722710945,0.219814378,2.73205594
+48.48889692,0.2154199579,-2.40879791,-0.3859875691,2.449020117
+48.49893792,-0.2521609557,-2.262403072,-0.9557589734,2.468912316
+48.50897792,0.4680802476,-2.364762091,-0.8532175219,2.557181848
+48.51901892,-0.1556884573,-2.531989096,-0.3870476693,2.566128129
+48.52905892,-0.5186447028,-2.601067517,0.3508960891,2.675382706
+48.53909992,0.6161733728,-2.796361304,0.9039929885,3.002750321
+48.54913992,-0.8005008528,-1.985783871,0.3524420929,2.169874335
+48.55918092,-0.2982808327,-1.483178118,-1.915339102,2.440760672
+48.56922092,0.2233338902,-2.523883393,1.662939945,3.030715208
+48.57926192,-0.03485346408,-3.810381934,1.168546752,3.985690249
+48.58930192,-0.3940380887,-2.542590683,1.649781371,3.056437791
+48.59934292,0.6723404107,-1.666672223,-0.4400895166,1.850274766
+48.60938292,-0.5370302857,-2.905204007,-0.4894131196,2.9946848
+48.61942392,0.2888723886,-3.348497213,0.6092266613,3.415704608
+48.62946392,0.1722061655,-3.007573843,-0.7094678181,3.09491518
+48.63950492,-0.09017093584,-2.652202295,-1.694379255,3.148528048
+48.64954492,0.3516773502,-2.020487973,-0.01271184683,2.050904727
+48.65958592,0.4170487095,-1.978315515,-1.31164683,2.409995708
+48.66962692,-0.1353253735,-2.699639879,-1.061620474,2.904032793
+48.67966692,0.09135662327,-3.103464087,0.5200928754,3.148067974
+48.68970792,-0.1370766694,-2.023828341,-0.484792065,2.085592126
+48.69974792,-0.007987134412,-1.447085448,-1.800908507,2.310279537
+48.70978892,-0.1125798051,-2.382017224,-0.002878584266,2.384677872
+48.71982892,0.2948391433,-2.630030238,0.8840282553,2.790250012
+48.72986992,-0.142697881,-2.06553887,-0.1287615359,2.074462109
+48.73990992,-0.2974492124,-1.159038522,-0.5344483745,1.310527144
+48.74995092,-0.3078361332,-2.008968228,0.2862603825,2.052476901
+48.75999092,-0.2997893229,-2.678768535,0.7966620827,2.810755232
+48.77003192,-0.4191798004,-2.222388968,1.240127197,2.579271194
+48.78007192,-0.1680558118,-1.760506293,1.148880812,2.108922067
+48.79011292,-0.3998365166,-1.90029714,0.7218767792,2.071739497
+48.80015292,-0.182139123,-1.986014982,0.991233446,2.227099889
+48.81019392,-0.3238097396,-1.780812212,-0.2219111896,1.82356504
+48.82023392,-0.4308404275,-1.757596719,0.4036824131,1.854111429
+48.83027492,0.735572347,-1.750504193,0.06769204617,1.899977321
+48.84031492,-1.12449763,-2.09409097,-0.4604641396,2.421102876
+48.85035592,0.02883590487,-1.131789108,-0.3756368279,1.192845808
+48.86039592,0.3950256469,-1.561596004,-1.247502875,2.037373496
+48.87043692,-0.2833250437,-2.129135233,-0.2358199614,2.160810259
+48.88047792,0.5208517343,-1.333065328,0.5591598773,1.536557667
+48.89051792,-0.4943163388,-0.9967399152,-2.092033188,2.36948137
+48.90055892,-0.1583272144,-1.90290529,-0.4645285392,1.965172464
+48.91059892,0.8393393748,-1.884086319,0.4242903399,2.105776374
+48.92063992,0.005509783344,-0.8973097672,-2.156090605,2.335363328
+48.93067992,0.1440269166,-1.21755329,-2.153007368,2.477623962
+48.94072092,0.2599694189,-1.845418974,1.535587589,2.414784573
+48.95076092,0.07952000412,-0.9804402168,-0.6106732625,1.157803214
+48.96080192,-0.5598157522,-1.007215056,-2.30925608,2.580802102
+48.97084192,0.1456942684,-1.107580978,0.4668446213,1.210746192
+48.98088292,0.06780178196,-1.475059112,-0.3009474188,1.5069724
+48.99092292,-0.3318834288,-1.071874005,-0.587204293,1.266439645
+49.00096392,0.5893139319,-1.076800869,0.9014184594,1.522940006
+49.01100392,-0.7274353617,-0.7319176179,0.07765160859,1.03484075
+49.02104492,0.01856682831,-0.6500166184,0.4885079706,0.8133304179
+49.03108492,-0.5348797528,-1.296418196,0.2211159682,1.419749541
+49.04112592,-0.2782269295,-0.8510365836,1.259162807,1.545045134
+49.05116592,0.4127336106,-1.024819341,0.08016357243,1.107713823
+49.06120692,-0.6350812217,-1.579726173,0.3691569436,1.742165259
+49.07124692,0.2672485994,-1.039032607,1.269946827,1.662460681
+49.08128792,-0.03704040496,-0.3207096921,-0.4365636456,0.5429682448
+49.09132892,-0.2454787029,-1.143214056,-0.5673196667,1.299634478
+49.10136892,0.4595709043,-1.876520461,1.575733402,2.493084477
+49.11140992,-0.3185632158,-0.7675335932,-0.5133662385,0.9767984613
+49.12144992,-0.05524197187,-0.2791727349,-1.026575187,1.065291371
+49.13149517,0.7068125244,-1.764372472,0.6702341706,2.015392768
+49.14153517,0.002084331382,-1.6083844,0.3836843508,1.65351698
+49.15157617,0.6409374274,-0.2867485154,-1.427740958,1.591059314
+49.16161617,-0.4636937395,-0.09798489902,-1.638561149,1.705724352
+49.17165717,0.2182236613,-1.574305804,1.372223985,2.099775939
+49.18169717,-0.2982443058,-1.377227008,2.308781286,2.704842866
+49.19173817,-0.5884193079,-0.2718296736,0.03032482982,0.6488823072
+49.20177817,0.1244694786,0.04674752983,1.616380906,1.621840071
+49.21181917,-0.4113900666,-0.3255238509,1.745219625,1.82236086
+49.22185917,-0.2777038412,-1.602127295,0.4213351572,1.679718609
+49.23190017,-0.07531480996,-0.5413917238,1.65399546,1.741975402
+49.24194017,-0.4066389846,-0.1933475776,0.9612091631,1.061443171
+49.25198117,-0.211492237,0.2671912784,-0.01762993991,0.3412198123
+49.26202117,0.31153563,-0.481366693,-0.008960857987,0.5734532578
+49.27206217,-0.5260603609,-0.5560967403,-0.3577461022,0.8449647102
+49.28210317,0.7634855658,-0.6618845659,-0.9512653881,1.387770596
+49.29214317,0.4216750997,-0.3793529162,-0.8409442163,1.01434989
+49.30218417,-0.003711773667,0.3263720626,-1.063228458,1.112199287
+49.31222417,0.710665401,0.6754897942,-1.734725043,1.992637134
+49.32226517,-0.40372243,0.2881087605,-1.239845946,1.33537127
+49.33230517,0.09074980105,0.1382542347,-0.3141632956,0.3550328662
+49.34234617,0.9496147192,0.1679175982,-0.9254809213,1.336592447
+49.35238617,-0.1735851582,-0.2495982673,-0.3193778425,0.4409459247
+49.36242717,-0.1887161808,0.09788931532,1.46447843,1.479828769
+49.37246717,-0.1814211398,0.479814038,0.7413515157,0.9015193901
+49.38250817,-0.8159118475,0.4653652392,1.287893686,1.594034848
+49.39254817,-0.4966064373,-0.1374875733,2.859059243,2.905123154
+49.40258917,-0.4115087651,-0.3104359149,2.05437595,2.118058183
+49.41262917,-0.3190130494,0.06089945908,2.142747844,2.167220891
+49.42267017,-1.131219297,-0.6425915316,1.721293988,2.157645469
+49.43271017,-0.4067728128,-0.6961822864,2.326258029,2.462033776
+49.44275117,0.9879579089,-0.06058313842,0.2673855704,1.025293221
+49.45279117,-0.9159930099,0.09142985051,-0.1525164342,0.9330937115
+49.46283217,-0.1462252321,-0.1361284794,1.408711195,1.422807089
+49.47287217,0.2030426084,-0.5967617132,-0.2197804642,0.6675734383
+49.48291317,-0.7717797681,0.09244566718,-0.3606615239,0.8568937779
+49.49295417,1.268897837,0.3288580795,-1.326625058,1.864988848
+49.50299417,0.1909205811,0.1139076164,-1.597990828,1.613381635
+49.51303517,0.1755862581,0.02356126411,1.102888368,1.117026597
+49.52307517,0.6204080725,-0.1188572114,0.1381375462,0.646618276
+49.53311617,-0.06512333692,-0.3950729362,-0.4947884649,0.6365055373
+49.54315617,0.2651497413,0.5575708964,-0.0376777035,0.6185542007
+49.55319717,0.419163684,0.6387655523,-0.9598976326,1.226834581
+49.56323717,0.3551872876,-0.511392657,-0.3727962506,0.7257117219
+49.57327817,0.3672433326,0.01056533396,0.5952056229,0.6994633837
+49.58331817,0.5358076694,0.3268478067,-1.899849828,2.000837004
+49.59335917,0.2475279692,0.08901039144,-1.566666709,1.588596086
+49.60339917,0.4197311197,-0.2065741622,-0.6085542315,0.7675840997
+49.61344017,0.2573011151,0.6539439739,-1.405695786,1.571568397
+49.62348017,0.554490364,0.5531289494,-2.538138905,2.656230468
+49.63352117,-0.1950397801,0.2436111387,-1.083712424,1.12774976
+49.64356117,0.1487574785,0.3605925268,-0.7058817208,0.8064891577
+49.65360217,1.04265313,0.2819895579,-2.712404058,2.919551238
+49.66364217,0.05779577072,0.0901378808,-0.7447200966,0.7523783695
+49.67368317,0.4702086706,0.4552722872,-0.009729766846,0.6545714001
+49.68372317,-0.2501765752,0.588722888,-1.073259357,1.24942731
+49.69376417,0.01821753027,-0.2631756848,-0.0880286622,0.2781049529
+49.70380417,0.523801143,-0.6237636434,0.563530671,0.9904622847
+49.71384517,0.1651698637,-0.01852862041,-0.1618538529,0.2319936709
+49.72388617,0.008718728442,0.2815851134,0.5308973604,0.601014309
+49.73392617,0.4296471204,0.1873235751,1.025570635,1.127600061
+49.74396717,-0.1946023718,0.03976097507,0.415549922,0.4605787185
+49.75400717,-0.3626400024,-0.4475623313,-0.1001534486,0.5846798483
+49.76404817,0.2516419788,-0.2717728459,0.4571054989,0.5883278018
+49.77408817,-0.0299202299,0.1416018935,-0.4359344852,0.4593312441
+49.78412917,0.3694469289,0.2490361672,0.2852552462,0.529037429
+49.79416917,-0.02855138758,-0.02584789088,1.121503564,1.122164666
+49.80421017,-0.8161417893,0.1883170901,0.1588296729,0.8525125287
+49.81425017,-0.3460101191,0.253909328,1.920668839,1.968034994
+49.82429117,0.2260937395,-0.02609347394,1.390003613,1.40851315
+49.83433117,-0.7695088557,0.2166850944,0.8844556868,1.192207269
+49.84437217,0.6477948227,0.2571767704,1.597234198,1.742680438
+49.85441217,0.5827936286,0.156339892,-0.1283808821,0.6169053625
+49.86445317,-0.3012355038,-0.2227484012,1.465378316,1.512512244
+49.87449317,0.3115826635,-0.7736210563,1.46207347,1.68322076
+49.88453417,0.004290814754,-0.07428944131,-0.03618490934,0.08274466657
+49.89457417,-0.8406248121,0.8429668412,-1.344879481,1.796091308
+49.90461517,0.7576353534,0.3605645698,0.2960340035,0.8897495541
+49.91465617,-0.02163619169,-0.8794289086,-1.099972361,1.408475249
+49.92469617,0.11723132,-0.4031521437,-0.08167449296,0.4277213534
+49.93473717,0.847803658,0.7065048147,-1.091064128,1.551883059
+49.94477717,-0.7687608507,0.5603357524,-2.258787008,2.450936178
+49.95481817,0.1281637312,0.05224328214,0.5299097657,0.5476857332
+49.96485817,0.02313656439,0.04911485732,-0.1366921145,0.1470792439
+49.97489917,-0.283015927,0.3928085654,-2.220848519,2.273007859
+49.98493917,0.2368563804,-0.4002331406,-0.2150237542,0.5123697168
+49.99498017,0.6980797078,-0.2532309779,0.05487261057,0.744615478
+50.00502017,0.3023503668,0.1470972895,-0.5636458611,0.6563154834
+50.01506117,-1.435523018,0.589971232,-1.482290803,2.146154331
+50.02510117,1.240467505,0.4923878174,1.098299473,1.728429092
+50.03514217,-0.3313032754,-0.1287093495,-1.383102145,1.42804044
+50.04518217,-0.5997624312,0.07221119469,0.7303388697,0.9477997125
+50.05522317,0.8806417673,-0.2090613119,0.5357142967,1.051772961
+50.06526317,-1.035864951,0.3899303466,-0.2486809123,1.134417942
+50.07530417,0.8452049361,0.7660988326,0.2686029607,1.171932744
+50.08534417,-0.126224493,-0.8773619179,-0.6642834592,1.10768636
+50.09538517,-0.6505496652,-0.4910380608,0.1724437451,0.83310869
+50.10542517,0.9657124693,0.3322397435,-0.2896283787,1.061540587
+50.11546617,-1.181308739,0.730487389,-2.051597938,2.477530275
+50.12550292,1.391133003,-1.005304917,1.682667866,2.403593176
+50.13554292,-0.3178314733,-0.7471140929,0.6375113976,1.032287312
+50.14558392,-0.04813321031,0.40666442,-0.7644883633,0.867257294
+50.15562392,0.6865382543,0.5851371196,-0.4031070471,0.988036191
+50.16566492,-0.1610792795,-0.3991812265,0.006395684481,0.4305032992
+50.17570492,-0.1117005483,-0.6745391831,0.2230923271,0.7192011599
+50.18574592,0.779909152,0.09210095555,0.1208514225,0.794572802
+50.19578592,-0.2705616318,0.5904190922,-0.4068311387,0.7663614529
+50.20582692,0.769845363,0.116318259,0.4402164012,0.8944172964
+50.21586692,0.09900897489,-0.423104817,0.3319066715,0.5467929241
+50.22590792,-0.4051443266,0.4236352691,-0.1528257519,0.6057759297
+50.23594792,-0.08176052012,0.5502419233,0.638275044,0.8466675785
+50.24598892,0.2733451622,-0.2977382659,0.9145489669,0.9998827259
+50.25602892,-0.3986698875,-0.08983317691,0.5312978947,0.6702873502
+50.26606992,-0.04006620887,0.4438579009,0.330548948,0.5548673214
+50.27610992,0.5219094956,-0.1064678933,0.4414712137,0.6918249536
+50.28615092,-0.12900806,-0.9947574898,1.315494298,1.654300696
+50.29619092,-0.2509358362,-0.3638590373,1.10485771,1.189988551
+50.30623192,0.1517768345,-0.1484245618,-0.1219881213,0.2448410909
+50.31627192,-0.3257405633,-0.3748242842,0.009902844429,0.4966872507
+50.32631292,0.7249240556,0.2646257577,-0.2375565845,0.8074495705
+50.33635392,0.4079954655,-0.3211341999,-2.045826151,2.110685224
+50.34639392,-0.2162033569,-1.181662788,-0.06698044002,1.203144719
+50.35643492,1.273527077,0.223890399,0.8986550653,1.574667919
+50.36647492,-0.9446887323,0.8814747763,-1.739018653,2.166476508
+50.37651592,0.1344824608,-0.06900907667,0.8132792848,0.8272067336
+50.38655592,0.4882201779,-1.101412238,1.667478554,2.057171016
+50.39659692,-0.5146968455,0.1260755443,-0.5613894206,0.7719883206
+50.40663692,0.3702823133,0.4547919749,0.0186871165,0.5867656605
+50.41667792,-0.5285390322,-0.3840606192,0.3411148667,0.7370314919
+50.42671792,0.1510746844,0.3572323512,0.9521290219,1.028099308
+50.43675892,-0.4864947742,-0.06845564685,-0.5916072464,0.769000959
+50.44679892,0.8090484589,-0.6855839887,0.7350680977,1.290313885
+50.45683992,-0.002784590274,-0.2792258167,0.1602417755,0.3219506752
+50.46687992,-0.2239638912,0.803757752,-1.526464763,1.739620941
+50.47692092,0.7335843667,0.2282809087,-1.549668853,1.729662323
+50.48696092,-0.9139583981,-1.068083548,0.2168112481,1.422367581
+50.49700192,0.113619842,-0.3338695818,0.9695765287,1.03172526
+50.50704192,0.6773596606,0.4079674355,-0.715938347,1.066687046
+50.51708292,-0.2677950582,0.02491835718,-1.256622777,1.285082068
+50.52712292,0.1792079869,-0.8856717615,0.7512947059,1.175148376
+50.53716392,-0.04766707758,-0.2079304969,-0.2414367968,0.3221784733
+50.54720492,-0.123582858,0.2758897974,-0.8491420126,0.9013490227
+50.55724492,0.3833617307,-0.1321488462,0.5919194877,0.7174944
+50.56728592,0.3294759109,-0.4179620446,-0.6444233912,0.8357799673
+50.57732592,-0.4174618519,0.5728447374,-0.9113289052,1.154532747
+50.58736692,0.1525423903,1.041677741,-0.6456045288,1.234976479
+50.59740692,0.3195457307,-0.8980445429,0.4502537316,1.054192534
+50.60744792,-0.09926951403,-1.198317632,1.51435284,1.933671148
+50.61748792,-0.07327442863,0.5878521645,0.2398960555,0.6391317756
+50.62752892,-0.04415846497,1.258638605,-1.157132403,1.710285504
+50.63756892,-0.08298947694,-0.4572176558,1.501012418,1.571296763
+50.64760992,-0.8775369689,-0.6065189985,0.2745788151,1.101512575
+50.65764992,0.3522408756,0.4527237417,0.01758959413,0.5738831018
+50.66769092,0.09389172016,0.5634109858,0.5448453087,0.7893693713
+50.67773092,-0.2770437454,-0.4267220508,0.479857015,0.6993623527
+50.68777192,0.6695225644,-0.490291079,0.4956760722,0.9666129396
+50.69781192,0.3008487836,0.09418186083,-0.7566320443,0.8196781466
+50.70785292,-0.1316782184,0.3872567803,-1.478563787,1.53409838
+50.71789292,-0.116954299,-0.782640825,-0.3289655221,0.8569849962
+50.72793392,0.5275429955,-1.062503842,-0.3104356956,1.226208118
+50.73797392,-0.07196752111,0.2085957639,0.588915773,0.6288984851
+50.74801492,0.2376231331,0.8111181539,-0.9491141975,1.27090329
+50.75805492,0.6426013988,-0.6477435865,0.7539949501,1.183645511
+50.76809592,-0.5577217181,-0.8903048028,-0.2377208912,1.07712923
+50.77813692,-0.09318492883,0.07611687893,-0.1842796791,0.2200822808
+50.78817692,-0.3605589053,0.4104705188,-0.1429264158,0.56472713
+50.79821792,0.5344328063,-0.3007821071,1.124028976,1.280441111
+50.80825792,-0.0001846623793,-0.7932996413,0.6506804967,1.026016308
+50.81829892,-0.479190871,-0.250287252,0.1093867868,0.5515732666
+50.82833892,0.755602642,0.2271029689,0.4607184935,0.9136589305
+50.83837992,-0.2506586599,-0.6089744271,-0.7578891957,1.004029705
+50.84841992,-0.3646370824,-0.8296280998,0.5142649555,1.041974774
+50.85846092,0.6416317112,-0.01820190724,-0.297523874,0.7074906486
+50.86850092,0.3075108453,0.1939537512,-1.631391878,1.671412707
+50.87854192,-0.1031583967,-1.276418672,-0.3877774018,1.33800508
+50.88858192,0.5538926689,-1.029307664,0.3547634375,1.221527098
+50.89862292,0.3102228935,0.04243185528,-1.217155825,1.256784393
+50.90866292,-0.3110734807,-0.09457673061,-1.325801185,1.36508617
+50.91870392,0.4865845655,-0.9909370653,0.571160118,1.242958039
+50.92874392,-0.2342329175,-0.7211830071,-0.8871594393,1.167056922
+50.93878492,0.3520220435,-0.02798203323,0.3035991311,0.465698342
+50.94882492,0.1765817831,-0.4922955411,0.6083419776,0.802256809
+50.95886592,-0.7986073051,-0.1830554548,0.09379343212,0.8246697128
+50.96890592,0.5185915297,0.4042522974,0.04868216336,0.6593383407
+50.97894692,0.6014815126,-0.8724309609,0.1532777417,1.070705308
+50.98898792,-0.8019001646,-1.421679442,1.060505995,1.946506942
+50.99902792,-0.02079805272,-0.3359788918,0.6929938728,0.770425131
+51.00906892,-0.3937876451,1.191572649,-0.06072859704,1.256424311
+51.01910892,0.2413339406,0.1576032925,-0.2773609203,0.4000124358
+51.02914992,-0.2211725035,-1.514727062,0.6943738157,1.680913545
+51.03918992,0.3155839498,-1.061015945,0.218344388,1.128282915
+51.04923092,0.7569768839,0.5293994865,-0.8291591531,1.241282691
+51.05927092,-0.5091533927,0.4501500166,-1.153118874,1.338489952
+51.06931192,0.3082013284,-0.7435480222,0.1212542957,0.8139744003
+51.07935192,0.1318671109,-0.5746832481,-0.7665676332,0.9670965344
+51.08939292,0.105560981,-0.5465535727,-0.2674791259,0.617583202
+51.09943292,-0.5178719567,-1.202005397,0.6448683643,1.459062557
+51.10947392,0.1897475749,-0.271818308,1.004849857,1.058117465
+51.11951392,-0.2954267336,0.105328673,0.2478681493,0.3997620589
+51.12955867,-0.4407116604,-0.9759076745,0.6111790466,1.232948654
+51.13959867,0.4931940754,-1.387129561,1.898930646,2.40277057
+51.14963967,-0.3357512158,-0.4434006487,-0.6079133767,0.8239488381
+51.15967967,-0.7618474683,0.3045811527,-1.265183101,1.507935516
+51.16972067,0.920203663,0.04724266566,0.4273618823,1.015699182
+51.17976067,-0.9681261268,-0.1708694189,-0.4734654236,1.091161795
+51.18980167,-0.1866397249,-0.1794444337,0.2026872987,0.3288112418
+51.19984267,0.6918820978,-0.8209517089,0.3444653213,1.127527784
+51.20988267,-0.5821700962,0.121613936,0.2311486208,0.6380765277
+51.21992367,-0.132028494,1.310217332,-1.163062649,1.756933609
+51.22996367,0.503161495,0.2516521018,-0.4421746337,0.7155548037
+51.24000467,-0.3023149729,-1.037739568,0.6593899244,1.266133021
+51.25004467,0.2977459221,-0.2031956958,1.474757835,1.518173836
+51.26008567,0.2242670693,0.801306453,-1.667984923,1.864017557
+51.27012567,-0.4405275827,0.1246185278,-1.063262372,1.15763604
+51.28016667,0.5510457692,-0.213944742,0.670271008,0.8936929096
+51.29020667,-0.5192491952,0.1816603274,-1.069973806,1.203106042
+51.30024767,0.03830723849,-0.1058817465,0.6387469143,0.6485954126
+51.31028767,0.1049247035,-0.6183614009,1.193785674,1.348519281
+51.32032867,-0.4750719461,0.04578176624,-0.06916963756,0.4822590205
+51.33036867,0.1361466515,0.5643855339,-1.079983655,1.226145031
+51.34040967,-0.04794206117,-0.7146373415,1.188286952,1.387454811
+51.35044967,-0.5801774016,-0.8830858304,1.110609616,1.532938394
+51.36049067,-0.04300768725,0.4174756659,-0.1022970378,0.4319725417
+51.37053067,0.08073806137,0.2870393413,-0.6070029652,0.6762860473
+51.38057167,-0.5255724473,-0.4782494693,1.135994133,1.339937171
+51.39061167,0.4883567104,-0.2436767737,-0.01179909647,0.5459027984
+51.40065267,0.05072751939,-0.305803166,-1.165417323,1.205937972
+51.41069367,0.1503204758,-0.04945594185,0.8542209041,0.8687551373
+51.42073367,0.31669715,0.4990693942,0.2075580293,0.6264564475
+51.43077467,-0.03455434931,0.2538099802,-1.142940626,1.171292783
+51.44081467,0.3493633877,-0.2668314371,0.6630619758,0.7955532517
+51.45085567,-0.1997412156,-0.1960166854,-0.4735203874,0.5500369546
+51.46089567,-0.004369222261,0.02491506812,-1.654600646,1.65479399
+51.47093667,0.5298367486,0.4120911112,-0.6584046686,0.9402354874
+51.48097667,-0.9372311204,0.008089394448,1.159603436,1.491022381
+51.49101767,0.5185878021,0.02068398633,1.335505809,1.43280735
+51.50105767,-0.1695741144,-0.5632040309,-0.2708208096,0.6475322939
+51.51109867,-0.6920928168,0.2647788817,-0.9516109586,1.206094416
+51.52113867,1.108523037,-0.1095485994,-0.0158751905,1.114036014
+51.53117967,-0.7298732851,-1.186754836,-0.1819986802,1.405071376
+51.54121967,0.01441102029,0.2405176876,2.01138839,2.025768914
+51.55126067,-0.1001742153,1.489100616,-1.169353668,1.896007257
+51.56130067,-0.3818306008,0.7185956141,-1.045548232,1.324894475
+51.57134167,0.02896662212,-0.4320551134,0.3540407217,0.5593348897
+51.58138167,0.4178757251,0.05409300313,-0.1357343405,0.4426849736
+51.59142267,0.7257656161,-0.07761589489,-1.354958326,1.539049064
+51.60146267,-0.2599270448,-0.1781747839,0.851117202,0.9075840533
+51.61150367,0.3048281427,0.4494662578,-1.128637751,1.252502809
+51.62154367,-0.6519630834,0.009490570044,0.07938530803,0.6568469839
+51.63158467,0.5219946823,-0.6468319324,0.348239699,0.9011885957
+51.64162567,0.1783887189,-0.4283277327,-0.2199979806,0.5135039368
+51.65166567,-0.1442099162,0.3411877742,-0.8230727863,0.9025820787
+51.66170667,0.263542561,-0.6272023179,0.4156306136,0.7972366248
+51.67174667,-0.7691368266,-0.3822644276,0.8807140535,1.230184862
+51.68178767,0.1614965514,0.773825051,-0.5502066207,0.9631270276
+51.69182767,-0.165879405,0.7705026631,-2.069715536,2.214703757
+51.70186867,0.3498240752,-0.3486008377,-0.3418878686,0.6006552608
+51.71190867,0.3251020474,-0.1477305704,0.4328798997,0.5611601111
+51.72194967,-0.2622948748,0.4141052943,0.02869638026,0.4910247227
+51.73198967,-0.5638323142,1.04957996,0.1204239911,1.197508626
+51.74203067,-0.6708614306,0.5794911212,0.768082062,1.172951437
+51.75207067,-0.2540521097,0.2757751554,-0.1491086769,0.4035192788
+51.76211167,-0.2079477279,-0.3612420063,1.111269767,1.186869217
+51.77215167,0.8359542755,0.004432331077,1.000810016,1.304016827
+51.78219267,-0.5389724018,0.02191244066,0.5216482347,0.750392088
+51.79223267,-0.02695131529,-0.09808272111,0.5773166513,0.5862091005
+51.80227367,0.09613555262,0.4731411955,0.5823850179,0.7564898839
+51.81231367,0.08014244023,0.8989075188,-0.9461134064,1.307512186
+51.82235467,-0.1358323545,0.1505815905,-1.214536858,1.231350893
+51.83239467,0.6153603905,-1.093053863,0.4007120275,1.316816345
+51.84243567,0.3742587123,-0.3073067409,-0.4288839126,0.6468758978
+51.85247667,-0.3501613499,0.247981366,-0.4411437696,0.6153986954
+51.86251667,-0.2840199122,0.5077814532,1.098387181,1.242965693
+51.87255767,-0.1676733308,-0.614661429,0.2177403706,0.6733007405
+51.88259767,-0.653613387,-0.8305947907,-0.2120276409,1.077986033
+51.89263867,0.3304924493,-0.4746457572,1.623321551,1.723277898
+51.90267867,0.04190369639,-0.7978933601,1.186704111,1.430613987
+51.91271967,-0.8355234819,-0.0527529218,0.7782082701,1.143018141
+51.92275967,-0.4615866223,-0.2210610775,-0.8487683755,0.9911296409
+51.93280067,0.05965005985,-0.8744695926,0.7627722055,1.161927982
+51.94284067,-0.001401102506,-0.600077523,-0.04955573738,0.6021218878
+51.95288167,-0.9080703981,-0.1547338263,0.7334817481,1.177510034
+51.96292167,-0.05711455182,-0.02225022928,-0.4751160926,0.4790536986
+51.97296267,-0.6474444283,-0.2635757622,0.0163037914,0.6992297789
+51.98300267,-1.055088184,0.06717071664,-0.07245869637,1.059704319
+51.99304367,-0.6193375205,0.1996978548,-1.081379385,1.262077482
+52.00308367,-0.2627182315,-1.071461484,-0.5790281314,1.245923014
+52.01312467,-0.1342396369,-1.106693443,0.1078881454,1.12001362
+52.02316467,-0.2855131266,-0.2632365872,-1.406975741,1.459586237
+52.03320567,0.666929909,0.6926560499,-1.931068697,2.157219094
+52.04324567,-0.750986046,0.3937098041,-1.651633769,1.856577916
+52.05328667,-0.01492917496,-0.8422505573,-0.7718166786,1.142501583
+52.06332667,-1.003110603,-1.117084457,-0.8329148197,1.71693205
+52.07336767,-0.6401454952,0.07114957787,0.5210097188,0.8284320397
+52.08340867,-0.5901819876,1.002815903,0.7512069976,1.38501497
+52.09344867,-0.76881216,-0.4864785117,-0.8898520821,1.272623357
+52.10348967,-0.07966697937,-0.5446837793,2.69156692,2.747282245
+52.11352967,-0.8978829405,-0.4502250437,0.5321328771,1.136688948
+52.12357067,-0.9447726399,0.2190846272,-1.13212737,1.490740016
+52.13360679,-1.289005242,-0.1732182819,0.5172756869,1.399683258
+52.14364779,-0.299039381,-0.9791955639,-0.03148199379,1.024323982
+52.15368779,-1.20397854,0.1323827439,0.3271622407,1.254641243
+52.16372879,-0.7170313378,0.7006320906,-0.8358103609,1.305219608
+52.17376879,-2.891046144,-0.6554624958,-1.432039831,3.2921903
+52.18380979,-1.66304885,-0.961684761,1.446325749,2.4046678
+52.19384979,-1.932051175,-1.49418594,0.2034889519,2.450881703
+52.20389079,-1.461029888,-0.05289902454,0.5592510939,1.565301385
+52.21393079,-1.952782917,0.3095812347,-0.5992331851,2.065982108
+52.22397179,-2.90492568,-0.7035868348,-1.398737015,3.300014072
+52.23401179,-3.26396197,-0.4572840583,1.129503724,3.484011354
+52.24405279,-2.935076555,-0.810360501,0.2051612556,3.051794499
+52.25409279,-3.354420151,-1.012697478,-1.096698505,3.671571644
+52.26413379,-2.852269749,-0.2293286932,0.6245691705,2.928842949
+52.27417379,-1.580540252,-0.02939094725,0.02657150209,1.581036799
+52.28421479,-2.73422499,-0.08893432282,0.6060095233,2.801989142
+52.29425579,-2.006163026,-0.3348892997,1.491103141,2.521949545
+52.30429579,-2.225611368,-0.8503659079,0.713758505,2.487150848
+52.31433679,-3.396884677,-0.6668240744,0.01321646154,3.461741546
+52.32437679,-1.799364257,-0.3775830737,0.6953596562,1.965656572
+52.33441779,-2.87375125,-0.2084686418,0.7907178032,2.987832001
+52.34445779,-1.841701753,-0.09501328007,0.8926628387,2.04883865
+52.35449879,-2.741811752,0.1553479849,0.503789084,2.792036554
+52.36453879,-2.447860673,-0.2451843138,1.311226416,2.7877324
+52.37457979,-1.787886173,-2.016151093,1.855354856,3.271657659
+52.38461979,-2.720097824,-1.199534656,1.381440951,3.278138903
+52.39466079,-2.294738613,0.5894837935,-0.6085214871,2.446142851
+52.40470079,-1.410805375,0.179115473,-0.6322997743,1.55636023
+52.41474179,-2.522709857,-1.325712892,-0.3182312036,2.867551359
+52.42478179,-2.712118714,-0.6056740027,0.1690295559,2.784061764
+52.43482279,-1.769942092,0.8838531312,-1.72107004,2.622207743
+52.44486279,-1.90648057,0.05157150102,-1.820289688,2.636433639
+52.45490379,-2.613671483,-1.164634819,-0.1419581169,2.864926699
+52.46494379,-2.304360499,-0.2124274809,-0.5947378457,2.389333767
+52.47498479,-1.926076929,1.110658952,-1.1943511,2.52384829
+52.48502479,-2.809178985,0.0820311457,0.5038955033,2.855192876
+52.49506579,-2.136267959,-0.6586328562,0.9860487199,2.443303115
+52.50510579,-1.456921927,-0.2535214018,-0.2416870576,1.498434929
+52.51514679,-3.508796292,-0.5375059567,-0.3166618109,3.563823617
+52.52518679,-2.08019857,-0.3060740748,1.735588092,2.726384686
+52.53522779,-3.05142299,0.1985736911,-0.6873214889,3.134170481
+52.54526879,-3.379623404,0.7470516738,-2.99328851,4.575993517
+52.55530879,-2.295291614,-0.1477418354,-0.3526584399,2.326920544
+52.56534979,-3.796228456,-0.5863713571,-1.403161603,4.089504168
+52.57538979,-4.091237443,-0.02153975832,-0.5355441427,4.126196227
+52.58543079,-3.241703667,-0.158243855,-0.08033723474,3.246557847
+52.59547079,-3.100383189,0.1707949765,-0.1077431345,3.106952755
+52.60551179,-2.984326775,0.3946514982,-0.3278036803,3.028103591
+52.61555179,-3.275398247,-0.496763362,-0.9490299976,3.44610874
+52.62559279,-3.677536118,-0.6857779701,-0.2511800122,3.749353907
+52.63563279,-3.208240052,-0.1372489521,-0.1217027771,3.2134799
+52.64567379,-3.976779658,0.07246557598,-1.470095265,4.240425426
+52.65571379,-3.790357267,-1.040376955,0.7488973475,4.00125476
+52.66575479,-3.196971298,-0.7874499406,1.160698619,3.491120762
+52.67579479,-4.633523425,0.4558146895,-0.2659734678,4.663480272
+52.68583579,-3.736829808,0.2920596145,0.5550890458,3.789105394
+52.69587579,-3.776318395,-1.11041103,2.778578167,4.818100238
+52.70591679,-5.286913814,-0.6499991499,0.1871763897,5.33000859
+52.71595679,-3.616357285,0.0667992677,-0.4521090531,3.645120678
+52.72599779,-4.269253,-0.8230588261,1.104564764,4.485979305
+52.73603779,-4.395346451,-0.4975189684,1.721768782,4.746691826
+52.74607879,-4.289308657,0.5453274116,-0.4789261383,4.350278265
+52.75611879,-4.630182911,0.2805024831,-0.940240463,4.733004073
+52.76615979,-4.574185296,-0.3312803982,1.592217287,4.854696048
+52.77620079,-5.219493663,-0.2598642969,-0.7385524535,5.277888146
+52.78624079,-5.51973123,0.3141976115,-0.5819406295,5.559209286
+52.79628179,-4.922561527,0.8041106314,0.06085255802,4.988176915
+52.80632179,-4.623773193,-0.09745808316,-0.2819001138,4.633383676
+52.81636279,-4.815155193,0.3500925355,0.1068701452,4.829048099
+52.82640279,-3.704159076,0.3794007172,-1.076995727,3.876165523
+52.83644379,-4.346634467,0.06985398106,-1.188928977,4.506846223
+52.84648379,-4.346851399,-0.1286145515,0.2291219759,4.354785375
+52.85652479,-3.893034374,-0.08071861938,-1.005015918,4.021478475
+52.86656479,-4.541010826,0.5043259314,-1.175318413,4.717679232
+52.87660579,-3.592246584,0.1018283926,0.2831385541,3.604826207
+52.88664579,-4.3539353,-0.2675438107,0.5623413473,4.398245114
+52.89668679,-4.966078261,0.00837984575,0.01407834113,4.966105286
+52.90672679,-4.477855926,0.1422401537,0.578768515,4.517344237
+52.91676779,-4.045302301,-0.9106375451,0.9455579209,4.252976749
+52.92680779,-4.513554347,-0.6452656826,0.5418725842,4.591532048
+52.93684879,-4.02731305,0.2847042009,-1.005882475,4.16078195
+52.94688879,-4.791328958,0.5351652066,-1.277514294,4.987512181
+52.95692979,-4.340551901,-0.2448536173,-0.5887853801,4.387141703
+52.96696979,-5.15560757,-0.03403125191,-1.200122302,5.293556562
+52.97701079,-5.10490227,0.4688012458,-1.387828449,5.310919845
+52.98705079,-3.961762547,0.04391204137,-1.073202054,4.104784208
+52.99709179,-4.615470439,0.04007025624,-0.6871823251,4.666518247
+53.00713279,-4.099875242,0.310500819,-0.5726903343,4.151308466
+53.01717279,-4.30552474,-0.4133282724,0.3122635353,4.336576076
+53.02721379,-5.002391224,-0.1457823421,0.757888611,5.061577382
+53.03725379,-4.026304405,-0.4826823531,-0.1492174351,4.057878172
+53.04729479,-3.718182745,-0.6193888298,0.7688521403,3.847032501
+53.05733479,-3.810677511,-0.7088067904,0.6711252862,3.933710628
+53.06737579,-3.467642418,-0.2833252995,-0.8232031792,3.575259521
+53.07741579,-4.325531573,-0.3572927237,-1.271933126,4.522797294
+53.08745679,-3.352429466,-1.049520319,-0.4906913209,3.546978178
+53.09749679,-3.699071998,-0.9688575404,-0.7152132922,3.890160489
+53.10753779,-3.689997119,-0.05500063718,-1.951471387,4.174607093
+53.11757779,-2.951583537,0.04188968134,-2.379100487,3.791268818
+53.12761879,-4.195860503,-0.4807167019,-2.404947519,4.860052106
+53.13765892,-3.997033536,-0.8771663285,-1.049208589,4.224516129
+53.14769992,-4.343909372,-0.8814866169,0.05775996566,4.432821167
+53.15773992,-4.432784711,0.06896944351,-0.5143134874,4.463054497
+53.16778092,-3.709233582,-0.4552914003,-0.2127714068,3.743123788
+53.17782092,-4.045875621,-1.57105446,2.038631737,4.795137226
+53.18786192,-4.347984881,-1.429021206,2.17011983,5.065224004
+53.19790192,-4.37708969,-0.7130124003,1.010138079,4.548371112
+53.20794292,-4.226325666,-0.7698671439,1.768440088,4.645632831
+53.21798292,-4.22985563,-2.037075793,2.219413612,5.192990778
+53.22802392,-4.25744981,-1.739355599,1.701008828,4.903536256
+53.23806392,-3.950779429,-1.564387903,1.566573738,4.528810096
+53.24810492,-3.459582909,-1.240024724,0.454969511,3.703157096
+53.25814592,-2.969768085,-1.265237626,-0.6189213449,3.286854479
+53.26818592,-3.31213104,-1.797599714,-0.4827239048,3.799289293
+53.27822692,-2.967955741,-2.031717843,-1.067291104,3.751766114
+53.28826692,-3.245518975,-1.846712671,-1.456076565,4.00797955
+53.29830792,-3.092111717,-1.446501604,-1.191025203,3.615530777
+53.30834792,-2.719277752,-1.415777263,0.3625694704,3.087127042
+53.31838892,-2.937762766,-1.724412747,-0.8647382909,3.514515856
+53.32842892,-2.844033653,-1.406020014,-1.404822797,3.469718546
+53.33846992,-2.089230326,-1.598994649,-0.5710776722,2.692173276
+53.34850992,-3.357955377,-2.818575461,0.1704855126,4.387402108
+53.35855092,-3.04142279,-1.525015092,0.2857592762,3.414320134
+53.36859092,-1.753385408,-1.290025727,-1.72995196,2.78051444
+53.37863192,-2.723557329,-2.118632611,0.5869528627,3.500126045
+53.38867192,-2.163944001,-2.528276699,0.09840805471,3.329342405
+53.39871292,-1.948053689,-2.157900465,-0.7687012821,3.007049925
+53.40875292,-2.586248041,-1.876432899,-0.9515881544,3.333946516
+53.41879392,-2.702567872,-2.104330614,0.6559833366,3.487462483
+53.42883392,-2.00714682,-2.040774303,-0.4981886208,2.905441449
+53.43887492,-2.38136906,-2.032439974,-0.4289400458,3.160019053
+53.44891492,-2.072870839,-2.434441752,-0.7949821776,3.294737747
+53.45895592,-1.822665997,-2.686608774,-0.4504192078,3.277629555
+53.46899592,-1.693535794,-2.902142113,0.05089825809,3.360518258
+53.47903692,-1.685216375,-2.869350343,-0.3256788021,3.343529917
+53.48907692,-1.262092116,-2.663391235,-0.2325051749,2.956448551
+53.49911792,-1.578529686,-2.228757755,-0.6199691659,2.800621157
+53.50915892,-2.154819567,-2.668651097,-0.1959513062,3.43559936
+53.51919892,-2.078737205,-3.120785294,0.4081754136,3.771877037
+53.52923992,-1.797836965,-4.006872938,-0.08054831922,4.392463606
+53.53927992,-1.166372831,-3.212269076,-0.399236775,3.44071042
+53.54932092,-0.8114077373,-2.661842307,-0.02246500254,2.782856745
+53.55936092,-1.768858749,-3.24118765,0.4342861551,3.717897675
+53.56940192,-1.417551893,-3.604490946,-1.390176691,4.115142717
+53.57944192,-1.780804318,-3.260045798,0.1422756207,3.717446028
+53.58948292,-1.830238726,-2.78118047,-0.1585168469,3.33314659
+53.59952292,-1.052092071,-2.824272111,-0.4978781337,3.054716569
+53.60956392,-0.3962486286,-3.187990267,-0.009401153326,3.212535338
+53.61960392,-1.925556527,-3.257066349,-0.6510377616,3.839283697
+53.62964492,-1.467608883,-3.343459545,-0.3701521397,3.670096752
+53.63968492,-1.166876641,-2.496378091,-0.3257916534,2.774823395
+53.64972592,-1.697846946,-3.458611394,0.08650078475,3.853849947
+53.65976592,-1.58955008,-4.048559493,0.03543178797,4.34956996
+53.66980692,-0.7057508893,-2.940497801,0.3693791378,3.046482001
+53.67984692,-1.639983484,-3.320864442,-1.326256683,3.93403651
+53.68988792,-1.692807084,-4.033334513,-0.2508484751,4.381359158
+53.69992792,-0.4909078141,-4.241332545,0.3989461684,4.288245595
+53.70996892,-1.324468605,-3.113361669,-1.702118629,3.787406209
+53.72000892,-1.330557018,-2.980024979,-1.568419704,3.620893705
+53.73004992,-0.1750298407,-4.013231493,1.338756861,4.234257006
+53.74008992,-1.308913403,-4.294981333,0.8398636508,4.567875863
+53.75013092,-1.635971856,-3.783609872,-1.453748204,4.37098289
+53.76017092,0.6331030355,-2.760452968,-2.799178492,3.981999532
+53.77021192,-0.2016375407,-2.465790721,0.2430588144,2.485932253
+53.78025292,-0.9278035815,-4.275406025,0.6045541513,4.416492034
+53.79029292,-1.372600545,-3.840319386,-0.3326650554,4.091790718
+53.80033392,-0.8943067834,-2.97949259,-0.6178782016,3.171582285
+53.81037392,-2.158841282,-4.601373972,0.5853302604,5.116233929
+53.82041492,-2.067694007,-4.693988605,1.855923205,5.454662086
+53.83045492,0.03698909336,-3.248655714,1.399009495,3.5372814
+53.84049592,-1.178589638,-3.614375664,-0.5585728168,3.842497699
+53.85053592,-2.439447845,-4.035774848,-0.7593393052,4.776502967
+53.86057692,-0.6480895223,-4.636438847,0.234296177,4.687374522
+53.87061692,-1.461735501,-4.409454321,0.6447683769,4.689955686
+53.88065792,-1.337648229,-3.796967837,-0.4836033261,4.054644215
+53.89069792,-0.9735933466,-4.161480922,0.3620876598,4.289162498
+53.90073892,-1.072465963,-3.235116778,-0.5680628479,3.455265433
+53.91077892,-2.164525506,-3.795414816,-1.341150711,4.570451786
+53.92081992,-0.863137104,-5.625402111,1.573441293,5.904733023
+53.93085992,-0.06809697499,-5.283781461,-0.7880649215,5.342661326
+53.94090092,-2.479261829,-4.200594116,0.1120420074,4.878963369
+53.95094092,-0.9168964778,-3.409380177,-1.83113218,3.977136835
+53.96098192,-1.942825401,-4.966933123,0.2223041224,5.338015953
+53.97102192,-1.108643417,-5.638472393,0.7743432605,5.798367756
+53.98106292,-1.042752532,-4.667433768,-1.441683059,4.995069655
+53.99110292,-1.607200778,-3.695361355,-0.4328886706,4.052922709
+54.00114392,-0.9337708113,-4.553980242,-1.235325463,4.81006164
+54.01118392,-2.066111458,-5.370131972,1.060191414,5.850738397
+54.02122492,-1.898014679,-5.077975257,0.2896494287,5.428829453
+54.03126592,-2.047883056,-4.005949078,0.5023927689,4.527013532
+54.04130592,-1.501924583,-4.449019213,-0.2423717666,4.701945713
+54.05134692,-1.962164044,-5.01508319,0.4676556301,5.405538727
+54.06138692,-1.487995054,-5.309029153,0.5225720948,5.538321174
+54.07142792,-1.819804515,-5.024363306,-0.4310070366,5.36112695
+54.08146792,-1.731712996,-4.392827178,-0.8278324199,4.793857219
+54.09150892,-1.982007447,-4.569152013,-0.6092570668,5.017638669
+54.10154892,-2.848825154,-5.265163926,-0.882004534,6.051089813
+54.11158992,-2.012167239,-5.633979392,0.2142028052,5.986353116
+54.12162992,-0.621962701,-4.243759432,-0.261235469,4.297042668
+54.13167071,-2.386293585,-3.850938222,-2.108628756,4.997042875
+54.14171071,-0.888586233,-4.686869035,1.011763605,4.876473361
+54.15175171,-2.042637372,-5.612386794,0.1220442545,5.973788393
+54.16179171,-2.893920051,-5.577626851,0.2959813786,6.290651757
+54.17183271,-0.6721655059,-4.56087411,-1.551175096,4.8641056
+54.18187271,-2.624413987,-4.463510368,-0.01329539895,5.177900187
+54.19191371,-2.245685444,-4.485208215,-1.211284636,5.160175028
+54.20195371,-0.9154054378,-4.865379267,-0.1162578499,4.952110501
+54.21199471,-1.879674449,-4.540559128,-1.373575276,5.10260348
+54.22203471,-4.029755724,-4.955669047,0.6390006834,6.419182875
+54.23207571,-0.4047790219,-4.08629333,0.5336537379,4.140824259
+54.24211571,-2.302970908,-4.260513459,-1.486951618,5.066228879
+54.25215671,-3.210653197,-4.70108157,0.8510131216,5.756099827
+54.26219671,-1.383928502,-5.19086745,0.4986324245,5.395275459
+54.27223771,-2.967716298,-4.266818804,-0.06720672727,5.197845657
+54.28227771,-2.667916687,-3.686696074,-0.2544404197,4.557877501
+54.29231871,-1.529402258,-5.139296762,-0.4462869805,5.380577528
+54.30235971,-2.653804432,-4.841723771,0.6646594352,5.561181458
+54.31239971,-2.277174162,-4.406572228,0.03986397743,4.960341733
+54.32244071,-2.180754453,-4.68772653,-1.047573123,5.275213688
+54.33248071,-2.770396743,-4.806919389,0.4443293327,5.565878249
+54.34252171,-2.008605992,-3.940888571,-0.3190895748,4.434740006
+54.35256171,-1.987196412,-4.493751875,-1.779603007,5.225872401
+54.36260271,-2.368528575,-4.643391479,-0.4528604203,5.232216986
+54.37264271,-1.816653159,-4.999536613,-0.5265201348,5.345354852
+54.38268371,-2.673169241,-4.783693956,-1.918103081,5.805917765
+54.39272371,-2.317365438,-4.477480535,-1.526830214,5.267753318
+54.40276471,-2.04908729,-4.774288418,-0.8221237832,5.260083282
+54.41280471,-2.161286733,-5.266589477,-0.4123842394,5.707730357
+54.42284571,-1.882412261,-4.704797183,-1.007749491,5.166638317
+54.43288571,-2.760297724,-5.063853062,-1.233219296,5.897684392
+54.44292671,-1.553297781,-5.087279931,-0.9889536166,5.410284683
+54.45296671,-1.745947165,-5.383276513,0.4127110988,5.674357053
+54.46300771,-3.059336904,-5.714076891,-0.2575622481,6.486644381
+54.47304771,-2.455430332,-5.30701888,-0.08574473977,5.848156947
+54.48308871,-2.65355271,-5.369059592,0.5064595073,6.010378035
+54.49312871,-2.914768883,-6.239535756,0.3311781085,6.894734442
+54.50316971,-2.952341336,-6.342165501,0.4383131325,7.009386635
+54.51320971,-2.299462871,-5.290195271,-0.04237301767,5.768491222
+54.52325071,-2.26355322,-5.29084899,0.04254258692,5.754873247
+54.53329071,-3.240003881,-6.376861709,-0.2888132769,7.158589492
+54.54333171,-2.498367606,-6.04016149,0.6633022964,6.570035118
+54.55337171,-2.877515102,-4.76159499,-0.6427282834,5.600533872
+54.56341271,-2.730086915,-5.430780462,-0.9186852872,6.147416827
+54.57345271,-2.564788175,-6.136254047,1.15075309,6.749517375
+54.58349371,-3.146918839,-5.290462489,-0.4142676276,6.169579337
+54.59353471,-2.777848727,-4.550724805,-1.323155905,5.493294216
+54.60357471,-2.50461331,-5.129741827,-1.246117669,5.842957152
+54.61361571,-3.042863836,-5.174325092,-0.4793050379,6.02182645
+54.62365571,-2.931046069,-4.774273215,-1.834056957,5.894784196
+54.63369671,-3.126667008,-4.78967712,-1.527475162,5.920323797
+54.64373671,-2.65902658,-5.330398387,-1.235548827,6.083596817
+54.65377771,-2.797880411,-4.941385469,-0.4969361472,5.70020795
+54.66381771,-2.546998314,-4.332041278,-3.574066713,6.166663192
+54.67385871,-3.136592949,-4.592173378,-0.2261662084,5.565736502
+54.68389871,-2.217896406,-4.63007883,-2.572660866,5.742410502
+54.69393971,-3.698514174,-5.076153265,-1.355943582,6.425334393
+54.70397971,-2.23735287,-4.261568589,-2.962992332,5.652082648
+54.71402071,-2.905086771,-5.180339538,0.007214879394,5.939318052
+54.72406071,-3.110594766,-5.827685952,-0.6694681853,6.639722209
+54.73410171,-2.775679117,-4.73819531,0.07669558883,5.491882334
+54.74414171,-3.007847493,-4.240073639,-2.209663965,5.648715415
+54.75418271,-3.138045397,-5.129130793,0.9820749521,6.092600661
+54.76422271,-2.36186538,-6.310475346,0.2505374032,6.74264608
+54.77426371,-4.335647256,-5.173593605,0.4698454124,6.76643648
+54.78430371,-2.389490843,-3.543671425,-0.4210802186,4.294715614
+54.79434471,-3.63403605,-4.318365811,0.5002485949,5.666105359
+54.80438471,-3.177595087,-5.110343104,0.8162075704,6.072800999
+54.81442571,-3.291726012,-5.143648844,1.632613946,6.321234996
+54.82446571,-4.043551645,-5.42148222,0.7592018956,6.805818605
+54.83450671,-2.782932881,-3.725877681,1.405363664,4.858181444
+54.84454671,-3.030099949,-3.121443398,-0.3591184437,4.365075102
+54.85458771,-3.609184506,-5.403602604,0.9691280472,6.569957615
+54.86462871,-2.30015065,-4.992356817,-0.2467688727,5.502291748
+54.87466871,-3.362160695,-3.786755674,-0.7183362901,5.114650535
+54.88470971,-2.684893493,-3.954750858,-1.870616089,5.133021719
+54.89474971,-1.96999595,-4.499780939,-0.8121186125,4.978799974
+54.90479071,-3.134192082,-4.635904411,-1.606869825,5.822095873
+54.91483071,-2.088496938,-3.829668975,-2.429728603,4.993171838
+54.92487171,-1.740789044,-4.189298758,-2.029329402,4.969783536
+54.93491171,-2.818673986,-5.489658415,-1.465530344,6.342637602
+54.94495271,-2.350058828,-4.755252515,-0.1087804306,5.305378041
+54.95499271,-1.730745866,-4.3175051,-2.036209236,5.077645084
+54.96503371,-3.148244695,-5.22409893,-1.225022085,6.221200319
+54.97507371,-1.963630818,-5.428797086,0.6234938675,5.806584917
+54.98511471,-2.801229988,-4.697971728,-0.1163736248,5.470957012
+54.99515471,-3.493657558,-4.188712867,-1.539435056,5.667523172
+55.00519571,-2.559654612,-5.229477199,0.2252154511,5.826661609
+55.01523571,-2.848949407,-5.484899951,1.029853721,6.26587894
+55.02527671,-3.743727184,-4.856461678,-0.4897031415,6.151465063
+55.03531671,-3.442604349,-3.910363474,0.2217872286,5.214561993
+55.04535771,-2.161215105,-3.91828002,0.974483512,4.579671075
+55.05539771,-3.418244848,-4.332155299,0.6456437051,5.555971848
+55.06543871,-3.531325906,-4.910242614,1.137962891,6.154324067
+55.07547871,-2.819694618,-4.354591066,2.260944046,5.659064328
+55.08551971,-3.558699354,-3.845842958,1.988977767,5.604541168
+55.09555971,-3.650588348,-3.819754144,2.228682033,5.734486952
+55.10560071,-2.79850577,-4.331022986,2.256418886,5.628571829
+55.11564071,-3.416084887,-4.554148934,2.550144408,6.238040155
+55.12568171,-2.664307786,-3.718676543,2.174501733,5.065130699
+55.13572179,-2.599240555,-3.48633509,0.776965152,4.417494614
+55.14576279,-3.054555928,-3.462151591,0.6104335266,4.657191712
+55.15580379,-2.170260309,-3.399243152,0.01276681066,4.032994769
+55.16584379,-2.142588069,-3.236627406,-1.234104565,4.073015428
+55.17588479,-1.641180409,-3.425544512,-1.920481144,4.256298411
+55.18592479,-2.234883737,-3.610717646,-3.12121214,5.270099853
+55.19596579,-1.568982791,-3.08023076,-2.355182451,4.182871372
+55.20600579,-1.658360845,-3.720755813,-3.931389477,5.661272625
+55.21604679,-1.801119299,-3.787490085,-3.164976211,5.254158951
+55.22608679,-1.116283316,-3.744769158,-3.639895837,5.340245892
+55.23612779,-1.73680212,-3.269795445,-3.516822472,5.106474729
+55.24616779,-1.32249707,-3.938807547,-3.801898209,5.63184103
+55.25620879,-1.732391711,-4.679643339,-2.494284203,5.578682327
+55.26624879,-1.044092568,-4.277710705,-2.329304429,4.981425226
+55.27628979,-1.546755332,-4.314480628,-2.383685873,5.166154613
+55.28632979,-0.8018857659,-5.197291785,-1.180034192,5.389558737
+55.29637079,-1.382122882,-5.20498906,-0.3901934713,5.399483839
+55.30641079,-1.128167489,-4.702676983,-0.8689044321,4.913545319
+55.31645179,-1.656514294,-4.707445387,-0.1798843271,4.99363996
+55.32649179,-0.7083765815,-5.524707211,0.8839721221,5.639644834
+55.33653279,-1.505782576,-5.651324573,0.2093601412,5.852237372
+55.34657279,-1.026151483,-4.502976442,-0.2704015642,4.626326913
+55.35661379,-1.365764127,-4.427843522,-0.6857433254,4.684159883
+55.36665379,-1.558463358,-4.900483903,0.1111187321,5.143529712
+55.37669479,-1.69333348,-5.239198195,0.6528024513,5.544612434
+55.38673479,-1.902138428,-4.748246381,0.06480235219,5.115483715
+55.39677579,-1.594315122,-4.570483716,0.3558615446,4.853637764
+55.40681579,-1.884670602,-4.328067218,1.208613628,4.872873488
+55.41685679,-1.671856218,-4.231999512,0.8858239353,4.63568842
+55.42689779,-2.02882888,-4.337771842,0.7546118313,4.847870687
+55.43693779,-1.424277068,-4.880638161,0.5373626268,5.112528984
+55.44697879,-1.686823921,-4.748054885,0.3382280964,5.05012855
+55.45701879,-1.298555353,-4.518457238,0.04913356841,4.701607802
+55.46705979,-1.602667724,-3.893921396,0.2932665163,4.221039318
+55.47709979,-0.9699449763,-3.638003385,-0.4481417173,3.791660967
+55.48714079,-1.260762606,-4.186218152,-0.7556292468,4.436769131
+55.49718079,-0.8699715489,-4.702519108,-0.084799245,4.783066733
+55.50722179,-0.8979216052,-4.488408104,-0.5129499167,4.605994804
+55.51726179,-1.314247818,-3.908189772,-1.29286382,4.321190979
+55.52730279,-1.196244794,-4.028553244,-1.121304758,4.349432976
+55.53734279,-1.167592194,-4.263961562,-0.2217679328,4.426490794
+55.54738379,-0.995106934,-4.068026336,-0.3558843488,4.203061949
+55.55742379,-0.6829293528,-4.174788307,0.2554478949,4.237983428
+55.56746479,-1.085851116,-4.029004065,-0.4959842205,4.202135974
+55.57750479,-0.915835866,-3.60752799,-0.8741242415,3.823232496
+55.58754579,-1.277971838,-4.094224785,-1.015271934,4.407569139
+55.59758579,-1.021062066,-4.334536578,0.6275781476,4.497180163
+55.60762679,-0.7523889392,-4.388400836,-0.4070480704,4.470999793
+55.61766679,-1.291590588,-3.851345188,-1.07255886,4.201362697
+55.62770779,-0.5683828733,-4.204769028,-0.8896883601,4.335283964
+55.63774779,-1.485989166,-4.862990679,-0.00551743269,5.084965348
+55.64778879,-0.8869073512,-4.786448872,-0.01124887347,4.867938372
+55.65782879,-1.044588119,-4.488237658,-0.3200514418,4.619293727
+55.66786979,-1.255252043,-4.442620605,-0.4160247159,4.635257501
+55.67790979,-0.6125675411,-5.044869491,-0.04583690822,5.082130282
+55.68795079,-1.04648766,-5.779030101,-0.5185252368,5.895862427
+55.69799179,-0.8021162923,-5.543869121,0.4083163315,5.616457745
+55.70803179,-0.7186126442,-5.132530364,-0.5057069707,5.207207659
+55.71807279,-1.624927927,-5.615657727,-0.2704044878,5.852274862
+55.72811279,-0.8188082658,-5.788422484,0.8630525386,5.909411266
+55.73815379,-1.067572501,-5.279446335,-0.10283849,5.387285068
+55.74819379,-0.8820157899,-4.496800613,0.176734432,4.585891698
+55.75823479,-1.302786398,-4.753036712,0.2265585566,4.933552388
+55.76827479,-0.7789410724,-4.641997795,0.2976127517,4.71629792
+55.77831579,-1.878135169,-4.558521482,-0.3525900275,4.942856416
+55.78835579,-1.562644263,-4.126162277,0.1829932916,4.415943702
+55.79839679,-1.124854384,-3.650576068,0.02614816368,3.820037532
+55.80843679,-0.927934486,-3.53192086,-1.089208807,3.810761498
+55.81847779,-1.191858505,-3.793092594,-0.5929953754,4.019915626
+55.82851779,-0.8494841478,-4.078715338,-0.65043199,4.216705337
+55.83855879,-1.150876028,-4.21420965,-1.682898831,4.68147702
+55.84859879,-1.232053362,-4.34607138,-0.1427048063,4.519585887
+55.85863979,-0.4438820207,-4.281575714,-1.153821124,4.456481239
+55.86867979,-1.075353829,-3.524856547,-0.3492343104,3.701751496
+55.87872079,-1.320541907,-3.695787325,-1.652511436,4.2583411
+55.88876079,-0.8164597316,-3.88283186,-0.5194414955,4.001600831
+55.89880179,-1.171481908,-4.418847873,-1.339666688,4.763747812
+55.90884179,-0.9927132301,-4.043263962,0.5793853962,4.20346886
+55.91888279,-0.6039108845,-4.196610116,-0.5946939915,4.281343921
+55.92892279,-1.071969607,-4.700921649,-0.7175410688,4.874694695
+55.93896379,-1.030832252,-5.102138876,0.3302805609,5.215699521
+55.94900379,-0.7811669612,-5.267658348,-0.06534731269,5.325665833
+55.95904479,-0.7470342784,-4.254822656,0.4579176772,4.344106887
+55.96908579,-0.6642639441,-4.403566175,1.222883758,4.618234113
+55.97912579,-0.5416650081,-4.97300955,-0.5088130116,5.028231861
+55.98916679,-1.157874999,-5.342599772,0.6232851219,5.502047908
+55.99920679,-0.5901423727,-5.173963149,-0.6544273925,5.248470053
+56.00924779,-1.148971663,-5.008060684,0.2763534451,5.145598014
+56.01928779,-0.1906674333,-4.799370049,0.1181669658,4.804609284
+56.02932879,-0.7074066746,-4.343051293,0.2170012826,4.4056337
+56.03936879,-0.146505332,-5.482966277,-1.25365473,5.62636945
+56.04940979,-1.192041084,-5.620479341,1.057490585,5.842006188
+56.05944979,-0.3922668209,-4.611413933,0.214205144,4.633022293
+56.06949079,-0.9863296786,-3.743231925,-0.7183631873,3.937089934
+56.07953079,-0.2713962487,-4.337849318,0.1967114443,4.350780162
+56.08957179,-0.4990989957,-5.140801835,0.5357125425,5.192680545
+56.09961179,-1.459082765,-4.40948765,0.2464466912,4.651154676
+56.10965279,-0.5887879383,-3.153144077,-0.406127134,3.233253479
+56.11969279,-0.7196930634,-3.081470954,0.1619275278,3.168539391
+56.12973379,-0.6467419584,-4.46753296,0.04082525969,4.514287608
+56.13977392,-0.8796102454,-4.119520133,-0.2822889537,4.221829859
+56.14981492,-0.6406215316,-3.915566619,-1.573670504,4.268313104
+56.15985492,-0.8084990399,-3.458422236,-0.1268886727,3.553935255
+56.16989592,-0.04024166645,-4.085801286,-0.1164683497,4.087659039
+56.17993592,-0.8034038492,-3.360013305,-0.2981910414,3.467573366
+56.18997692,-0.8584227133,-2.955241263,-2.245670534,3.809642585
+56.20001692,-0.2194400283,-3.454309305,-1.301821754,3.697992236
+56.21005792,-0.115054968,-4.05299022,-0.6204468834,4.101819317
+56.22009792,-0.4792919547,-3.851845417,-1.36400163,4.114235572
+56.23013892,0.1504753174,-3.262564778,-1.616727646,3.644280455
+56.24017892,0.1657446084,-4.098281291,-1.289234453,4.299477444
+56.25021992,-0.3352465646,-5.180867541,0.4589725149,5.211951123
+56.26025992,-0.3740320962,-4.706521235,0.2553063923,4.728257977
+56.27030092,-0.1615802032,-3.750245368,-0.3258472019,3.767840878
+56.28034192,-0.07532258037,-3.426505795,-0.2720797151,3.438116173
+56.29038192,-0.1603500952,-4.675030763,0.4507753032,4.69944924
+56.30042292,-0.6025298452,-4.840660747,0.328925761,4.889093049
+56.31046292,-0.6785220871,-4.167819303,0.9261358094,4.323058813
+56.32050392,-0.6540138482,-3.483585729,-0.4282220078,3.570220964
+56.33054392,-0.5541128531,-4.216202089,0.3220131826,4.26463288
+56.34058492,-0.4027381609,-4.846629293,0.649825049,4.906555423
+56.35062492,-0.373456182,-4.816496544,0.4569827074,4.852519106
+56.36066592,-0.4857042307,-4.602967046,-0.4172491229,4.647290722
+56.37070592,-0.4249994976,-3.819102179,0.2679656142,3.852008774
+56.38074692,-0.234898221,-3.902370331,-0.5103350419,3.942602342
+56.39078692,-0.3105578659,-4.336470837,-0.04727473855,4.34783399
+56.40082792,-0.105521823,-4.698247132,0.07559163451,4.700039901
+56.41086792,-0.4056985331,-3.83077059,-0.8004206729,3.934471739
+56.42090892,-0.4142208499,-3.276592833,-0.388826977,3.325481307
+56.43094892,-0.4046254594,-3.70464761,-0.230791356,3.733818465
+56.44098992,-0.3588080297,-4.391444312,0.3428117287,4.419394328
+56.45102992,-0.4648263452,-4.583091775,-0.1864723849,4.610375874
+56.46107092,-0.1969710241,-3.974905626,-0.1340690535,3.982040536
+56.47111092,-0.09568387348,-3.645656221,-0.2623212969,3.65633384
+56.48115192,-0.6037739865,-3.593668919,-0.07245109499,3.6447563
+56.49119192,-0.4046655128,-3.508189351,-0.4452110928,3.55940439
+56.50123292,-0.2755085224,-3.785429818,-0.5250612545,3.831588858
+56.51127292,-0.2997458525,-3.80471949,0.1170302671,3.81830251
+56.52131392,0.03907713864,-3.80716655,0.02628206491,3.807457802
+56.53135392,-0.7376649924,-3.438304014,-0.2216468954,3.523522595
+56.54139492,-0.2899820074,-2.896323549,-0.1306864393,2.913736194
+56.55143492,-0.1006062789,-3.336389384,0.03793439627,3.338121442
+56.56147592,-0.8228639676,-3.583980375,0.0272252208,3.677330778
+56.57151692,0.3643885757,-3.219335728,0.0451557076,3.240206876
+56.58155692,-0.2750266387,-2.947444001,-0.6711603695,3.0353784
+56.59159792,-0.3355117723,-3.066863733,-0.7645018119,3.178472011
+56.60163792,0.101577611,-3.289636802,0.3001773405,3.304865313
+56.61167892,-0.1381631552,-3.084131438,-0.5248162562,3.13151527
+56.62171892,0.01403355968,-2.765440058,-0.7615314263,2.868411715
+56.63175992,-0.3845061039,-3.351188979,-0.2503766048,3.382454872
+56.64179992,-0.4709078515,-3.068798284,0.02980033457,3.104861538
+56.65184092,-0.2885904066,-2.856390574,0.03120892882,2.871101797
+56.66188092,0.05731087666,-3.297187311,0.07571851909,3.298554531
+56.67192192,-0.0846697109,-3.261404983,0.7490780264,3.347394406
+56.68196192,0.3167168843,-3.059398592,-0.5959499735,3.132951596
+56.69200292,-0.2220774149,-3.051262192,-0.6715287441,3.132167013
+56.70204292,-0.3176089502,-3.168165282,0.2538697314,3.194150363
+56.71208392,0.3035010258,-2.665392736,-0.02511671484,2.682734083
+56.72212392,-0.4808324768,-2.397776347,-1.028621712,2.653034849
+56.73216492,0.5731930121,-3.188239358,0.1431708294,3.242517281
+56.74220492,-0.1799309221,-3.181729945,0.2649098593,3.197805156
+56.75224592,-0.4303842716,-2.219769415,-0.285016095,2.279000011
+56.76228592,-0.0870200175,-2.055203185,0.4587918359,2.107586905
+56.77232692,-0.1930685558,-2.692025342,0.4377260721,2.734205556
+56.78236692,-0.2655676345,-2.51127972,0.4126105267,2.558769127
+56.79240792,-0.2650641344,-2.608250237,0.1300034845,2.62490556
+56.80244792,0.6504565483,-2.745172147,0.2883794135,2.835881966
+56.81248892,-0.02974429723,-2.415947593,0.6007780194,2.48970314
+56.82252892,-0.4750187364,-1.829523465,-0.06219741762,1.891207928
+56.83256992,0.3957306384,-2.192845618,0.343016966,2.254514423
+56.84260992,0.1478297629,-2.50429639,-0.6858111531,2.600709708
+56.85265092,-0.1094118933,-2.572429024,0.3040774333,2.592648286
+56.86269092,0.446384629,-2.308534095,-0.130594638,2.354919078
+56.87273192,0.1337144473,-1.731227823,-1.039477653,2.023744826
+56.88277192,0.3534440864,-1.783210593,-0.5544657326,1.900577541
+56.89281292,-0.05547079443,-2.389560425,0.0271141237,2.390357966
+56.90285392,0.6156980672,-1.913387009,0.07476542294,2.011398475
+56.91289392,0.08846854641,-1.977910595,-1.430165214,2.442402413
+56.92293492,0.1315441344,-2.402685377,0.4387487501,2.445956121
+56.93297492,0.8146343771,-2.01985355,0.5992717767,2.258885609
+56.94301592,-0.007881804588,-1.689646518,-0.9333471805,1.930312006
+56.95305592,0.007049179352,-2.260526555,0.2745437318,2.277148273
+56.96309692,0.5633338756,-1.687910626,0.6630537897,1.898954361
+56.97313692,0.1525162515,-1.615886963,-1.109201022,1.96587863
+56.98317792,0.2220360642,-2.24081676,0.1367277825,2.255937555
+56.99321792,0.45735269,-1.758110251,0.818190946,1.992375356
+57.00325892,0.2116256449,-1.274312943,-0.1722192121,1.303195437
+57.01329892,0.1949733229,-1.054376943,-1.090468297,1.529328755
+57.02333992,0.4119229307,-1.965193778,0.6701295054,2.116776002
+57.03337992,0.228355278,-1.512915448,-0.09138204038,1.532778511
+57.04342092,0.4582606895,-0.9601245777,-0.5735691708,1.208645381
+57.05346092,0.1538475894,-0.8719342399,0.4091191542,0.9753547467
+57.06350192,0.2146073777,-1.275856608,0.3318797743,1.335668595
+57.07354192,0.3759367536,-0.3476287015,-0.4167029929,0.6601632685
+57.08358292,0.2635198848,-0.5361394624,-0.7569320065,0.9642791687
+57.09362292,0.4096799387,-1.195667162,0.569488399,1.38628087
+57.10366392,0.442898117,-0.6427703834,0.01118572354,0.7806648629
+57.11370392,0.2315658745,-0.1137812343,-0.9957100743,1.028594904
+57.12374492,0.55366587,-0.02318769555,-0.2075404876,0.5917403306
+57.13378442,0.4586755494,-0.3431951599,0.4200189489,0.7103394223
+57.14382542,-0.2198189462,-0.3400814079,-0.5670933795,0.6968289849
+57.15386542,0.5505479519,0.07499164623,0.1877283669,0.5864884774
+57.16390642,0.4605670871,0.2422464352,0.1776425046,0.5498747462
+57.17394642,0.464260956,-0.2743544647,0.3160858601,0.6250750983
+57.18398742,0.8227764056,-0.1989276486,0.4188980377,0.9444621691
+57.19402742,0.2788104085,0.3802859126,0.04346469283,0.4735417603
+57.20406842,0.2498987046,0.03355252027,0.1270132184,0.2823251526
+57.21410842,0.8165972143,-0.3880234599,0.5942133504,1.081888498
+57.22414942,0.3411059132,-0.2438448995,0.3089300376,0.5208179597
+57.23418942,0.5503755687,0.4861503367,-0.6146037608,0.9575976187
+57.24423042,0.6642465486,-0.1934986368,-0.1858403009,0.7163810559
+57.25427142,0.7383741865,-0.3849344856,0.7234093344,1.103037652
+57.26431142,0.7149621543,0.2736673255,0.347746194,0.8408282242
+57.27435242,0.7063720098,0.2580421035,-0.5804051507,0.9499564634
+57.28439242,0.4933348471,-0.2471036624,0.03697019041,0.5529975464
+57.29443342,0.6513757306,-0.2260283785,0.9889161944,1.205543201
+57.30447342,0.8006757577,0.02191127121,-0.7574424684,1.10239778
+57.31451442,0.3634310576,0.1314543066,0.2582773626,0.4648328349
+57.32455442,0.9496787462,0.2135913874,0.5168739831,1.102120554
+57.33459542,0.2761389071,0.3769683851,-0.1904619402,0.5046123364
+57.34463542,0.947966316,0.1913612785,-0.1228383064,0.9748582075
+57.35467642,0.7289309333,-0.0258293077,0.3745287806,0.8199263784
+57.36471642,0.6875928728,-0.04093348799,-0.2877379739,0.7464935705
+57.37475742,0.8519130081,0.4859408967,-0.1454301935,0.9914858898
+57.38479742,0.5615650564,0.5857350339,-0.9675463754,1.262769508
+57.39483842,0.7771107477,0.1653131387,-0.1990789819,0.8190616516
+57.40487842,0.8483823862,0.2048919913,-0.01024139822,0.8728334821
+57.41491942,0.4968427014,0.3414425301,-0.3966142988,0.7216221818
+57.42495942,0.8953635214,0.2887123028,-0.0235701263,0.9410558858
+57.43500042,0.6997661179,0.3248945443,-0.1406740683,0.7842310108
+57.44504042,0.4226338238,0.3792230715,0.1281101561,0.5821011072
+57.45508142,0.7036841179,0.6322741927,0.1216302717,0.9538007735
+57.46512142,0.8180683006,0.3644242072,0.06189453185,0.8977035593
+57.47516242,0.5617865197,-0.09656585287,0.3039049405,0.6459777631
+57.48520242,1.068813719,0.3254458271,-0.08218203127,1.120281946
+57.49524342,0.3074024525,0.4530053582,-0.8821401894,1.03821069
+57.50528342,0.7620706127,-0.0593098798,-0.1987094378,0.7897814389
+57.51532442,0.6747023935,0.02199817546,0.3764659631,0.7729384587
+57.52536442,0.5251931823,0.5456981616,-0.9218661726,1.19308491
+57.53540542,0.8656060177,0.6676509438,-0.584243263,1.239504639
+57.54544542,0.7092649198,-0.226266342,0.1730898625,0.7643384619
+57.55548642,0.881660133,-0.06156043656,-0.5847852999,1.059758522
+57.56552642,0.7459730818,0.4769959358,0.09631241262,0.8906610143
+57.57556742,0.8815329561,0.5575722852,-0.4871642804,1.151223802
+57.58560742,0.6396965752,-0.03609135389,-0.448698957,0.7822052468
+57.59564842,0.7870271869,-0.1963922594,-0.09113821149,0.8162645932
+57.60568942,0.9504777682,0.4659184589,-0.4899966717,1.166441056
+57.61572942,0.6572581758,0.4683351497,-0.9823696518,1.271367868
+57.62577042,0.9395009364,-0.2024309713,0.3931691194,1.038374819
+57.63581042,0.8639740598,-0.137144287,-0.2438949662,0.9081544395
+57.64585142,0.7238213439,-0.1592900315,-0.7005584157,1.019839569
+57.65589142,0.9100384978,-0.1429223593,0.3704866004,0.9929034139
+57.66593242,1.044057192,-0.4750577666,-0.7102875978,1.349164102
+57.67597242,0.4000923323,-0.470316698,0.3095475036,0.6907179799
+57.68601342,1.316428099,-0.5593862011,0.8766940928,1.677643703
+57.69605342,0.4377088228,-0.6620093308,0.01026712596,0.793694388
+57.70609442,0.5566757243,-0.4987817112,0.6530170441,0.9925232074
+57.71613442,1.176776635,-0.5431622242,0.2870959496,1.327498601
+57.72617542,0.4902300121,-0.6223902056,-0.2987026727,0.8467102925
+57.73621542,1.219263747,-0.9991606624,0.257745266,1.597297322
+57.74625642,0.8371267884,-1.206721981,0.9863358182,1.769129036
+57.75629642,0.682139394,-0.3934469717,-0.5866412061,0.9819687251
+57.76633742,0.8816559669,-0.3039728413,-1.139848033,1.472742432
+57.77637742,0.5564158521,-1.227706395,0.9073317486,1.624842299
+57.78641842,1.243498117,-1.538722135,0.1568737793,1.984581255
+57.79645842,0.8635653394,-0.6773138331,-0.5207816774,1.21478915
+57.80649942,0.7011223065,-0.4339538505,-0.2406450838,0.8589519715
+57.81653942,1.275444672,-1.256101352,0.02909574509,1.790362052
+57.82658042,0.6001227658,-1.396848218,-0.2553063923,1.541594509
+57.83662042,0.8784027223,-0.7391190487,-0.8707837272,1.44088605
+57.84666142,1.295755852,-0.8738555619,-1.327773451,2.050753303
+57.85670142,0.7897894116,-0.8454622867,-0.1664713991,1.168882594
+57.86674242,0.9687902243,-0.729343235,-0.4331634897,1.287682671
+57.87678242,0.5323690315,-1.385358731,-0.2207253742,1.500451696
+57.88682342,0.7964122604,-0.5181440349,-0.4166983151,1.037488899
+57.89686342,0.4587271876,-0.4553153373,0.1845159066,0.6721523702
+57.90690442,0.6299684163,-0.9794105952,-0.3035751575,1.203438073
+57.91694442,0.2719054316,-1.480961146,1.126235715,1.88031523
+57.92698542,0.8091423067,-0.4914696218,0.7694970882,1.21999157
+57.93702642,0.448060039,-0.1964787251,-0.478741951,0.6845111713
+57.94706642,0.7596120047,-1.066959859,0.3602563119,1.358380782
+57.95710742,0.2563648845,-1.28511699,1.141443154,1.737855317
+57.96714742,0.746655525,-0.4055061231,-0.1627057922,0.8651028053
+57.97718842,0.1907607877,-0.2697887029,-0.3930773181,0.5135030675
+57.98722842,1.170672215,-1.511668676,0.8137488163,2.077932327
+57.99726942,0.4069373753,-1.826659645,0.8199942273,2.043201903
+58.00730942,0.9375047701,-1.045088349,-0.3585290444,1.449023094
+58.01735042,0.590944903,-0.687226764,-0.373152346,0.9801730342
+58.02739042,0.5575985245,-1.639070296,0.659325605,1.852613776
+58.03743142,0.9774930009,-1.999743368,0.450975278,2.271088903
+58.04747142,1.086395127,-1.405201696,-0.7671839297,1.934791296
+58.05751242,0.7200246006,-1.135887275,-0.4106803608,1.406176976
+58.06755242,0.8604689464,-1.991323523,0.1704714793,2.175967993
+58.07759342,0.9554578418,-2.16386711,-0.8707392883,2.520596648
+58.08763342,1.239451113,-1.076433518,-0.9675574851,1.905548652
+58.09767442,0.7365952443,-1.348571266,-0.9557958108,1.809630528
+58.10771442,0.6761388351,-1.472834247,0.02066055179,1.620750228
+58.11775542,1.236506162,-0.8760450518,-0.7227877754,1.678935553
+58.12779542,-0.3305256323,-1.432417854,-0.5779469812,1.579585646
+58.13783692,0.791481742,-1.377564539,1.117191827,1.942226811
+58.14787692,0.9114549127,-0.9795526095,0.6391556346,1.482832862
+58.15791792,-0.4844303782,-1.397269363,-0.2889372379,1.506824208
+58.16795792,1.138707972,-1.273262929,2.167240076,2.759489786
+58.17799892,0.6547668234,-1.204408603,-0.2441645229,1.392456818
+58.18803892,-0.5780240183,-0.8931808289,0.1686804771,1.077189334
+58.19807992,1.345496069,-1.219234511,1.305697289,2.236456544
+58.20811992,0.2451878222,-1.657637836,-0.2812031257,1.699104312
+58.21816092,-0.08528541357,-0.9234169272,-0.006575778723,0.927370295
+58.22820092,1.215435502,-0.871336289,0.2871000427,1.522805576
+58.23824192,0.1997352039,-1.52910405,-0.0621401149,1.543345308
+58.24828192,0.8637478457,-1.687917204,0.3147328144,1.922025383
+58.25832292,0.5340521526,-1.074187821,-0.0662612325,1.201449844
+58.26836292,0.3867140125,-0.8354509764,-0.9961100239,1.356377986
+58.27840392,0.9713548131,-1.643193313,0.1403349298,1.913977098
+58.28844492,0.6186733498,-1.926072982,0.3153105193,2.047421444
+58.29848492,0.4877650818,-1.087913575,-0.05906974196,1.193716866
+58.30852592,0.6946587943,-0.7029647642,0.02972899854,0.9887335908
+58.31856592,0.6124793578,-1.444263143,0.1500027162,1.575921256
+58.32860692,0.8167424445,-1.814074683,-0.2842109334,2.009654455
+58.33864692,0.2165121995,-1.532217838,-0.5772751361,1.651610008
+58.34868792,0.8278764202,-0.4930337155,-0.6711106682,1.174244924
+58.35872792,0.7360200975,-0.6565101707,-0.7185251552,1.220249805
+58.36876892,-0.1037939981,-1.338594601,0.2140800136,1.359573077
+58.37880892,0.6262132613,-1.203671342,1.308167152,1.884746415
+58.38884992,0.7357643549,-0.5056523723,-1.039126235,1.369969649
+58.39888992,-0.004857674902,-0.6194225243,-0.2198097003,0.6572854517
+58.40893092,0.9227400389,-1.678898751,0.8989807552,2.116203344
+58.41897092,0.271269419,-1.430998442,0.5440483332,1.554777228
+58.42901192,0.2785655746,-0.6553138304,-0.2958410454,0.7710751713
+58.43905192,0.5230435997,-0.6626795679,0.5427888429,1.003662565
+58.44909292,0.1763598447,-1.431289341,0.1334200126,1.448272375
+58.45913292,0.4203991641,-1.311608385,0.1742932194,1.388319178
+58.46917392,0.6593511866,-0.7842583841,-0.2022855949,1.044377643
+58.47921392,0.6864979816,-1.131313291,0.1967009193,1.337849204
+58.48925492,0.2484169105,-1.490537716,0.7252927226,1.676145333
+58.49929492,0.675535841,-0.8095855987,-0.5590405941,1.193442039
+58.50933592,0.4837997925,-0.5491414773,-1.257168322,1.454678931
+58.51937592,1.040013916,-1.323729809,-0.5643913811,1.775507585
+58.52941692,0.7333144446,-1.61016093,0.01156169951,1.769322461
+58.53945692,0.79092019,-0.6709023611,-1.731798511,2.018611109
+58.54949792,0.2574982576,-0.3546502939,-0.7730574578,0.8886506719
+58.55953792,0.9973278527,-1.352220367,0.7860932404,1.855021658
+58.56957892,-0.01627463755,-1.825865008,0.1453804922,1.831715966
+58.57961892,0.6084285164,-1.064759478,-0.5058128053,1.326553655
+58.58965992,0.8000580724,-0.4863101484,-0.4300808376,1.030320342
+58.59969992,0.3564605919,-1.237314248,0.1629852891,1.297911748
+58.60974092,0.7056147954,-1.778783082,0.6722233933,2.028261764
+58.61978092,0.614194675,-1.404795753,-0.2420840836,1.55218907
+58.62982192,-0.05258201865,-1.027858066,-0.379656204,1.096994032
+58.63986192,0.690096285,-0.6847461558,-0.1211326736,0.9796853092
+58.64990292,0.5637821744,-1.288279018,-0.3101801723,1.44004337
+58.65994392,0.4431529826,-2.116296064,0.2921824425,2.181848797
+58.66998392,0.9020910354,-1.253514982,1.154935019,1.928456104
+58.68002492,0.2058796591,-0.396234778,-0.6455396247,0.7849266465
+58.69006492,0.02511250758,-0.8634940034,-0.4054482722,0.9542750303
+58.70010592,0.7279746211,-1.727766856,0.8376563269,2.053483255
+58.71014592,-0.09851356041,-1.306746864,0.5199578047,1.409839851
+58.72018692,0.7089983598,-0.8976769723,-0.2353726494,1.167862537
+58.73022692,0.8314234874,-1.830743048,0.5615993357,2.087649141
+58.74026792,0.2614865155,-2.230986129,0.3071179855,2.267155875
+58.75030792,0.5660081728,-1.289370401,-0.07878421426,1.410336213
+58.76034892,0.2660496461,-0.7888735183,-0.3958009511,0.9218254905
+58.77038892,0.2650235876,-1.538774175,-0.08082898557,1.563520639
+58.78042992,0.4797224194,-1.444702415,0.7423127979,1.69361358
+58.79046992,0.7075255924,-1.191301484,-0.8487408936,1.6248547
+58.80051092,0.2571493433,-1.217193175,-0.3060988158,1.281164117
+58.81055092,0.6247279224,-1.131990764,0.1673414648,1.303722069
+58.82059192,0.5382670814,-0.7363571164,-0.7240765017,1.164577191
+58.83063192,0.06021849143,-0.7292974075,-1.092012547,1.314531239
+58.84067292,0.9721459414,-1.413514975,0.5636786056,1.805775702
+58.85071292,0.4899400268,-1.389282359,-0.3461820638,1.51327087
+58.86075392,0.2022911681,-0.6536785103,-0.2834888023,0.7406640349
+58.87079392,0.70071344,-0.3795432796,-0.3441150731,0.8680251204
+58.88083492,-0.01421417469,-0.8208496749,0.3397904724,0.8885121253
+58.89087492,-0.03002621982,-1.189828863,0.4352708262,1.267302249
+58.90091592,0.4281621103,-1.415370881,0.9361614454,1.750141645
+58.91095592,0.5843193499,-1.273102862,0.4508735365,1.471566154
+58.92099692,0.3806374399,-0.7889426617,0.6838137442,1.111268024
+58.93103692,0.2258408839,-0.5332252832,-0.4772731304,0.7504151841
+58.94107792,0.4709179014,-0.6787238891,-0.7163219243,1.093410667
+58.95111792,0.267756558,-1.21950838,-0.3387870902,1.293704354
+58.96115892,0.08909115611,-1.30360647,0.3677483493,1.357411475
+58.97119892,0.3789656844,-1.193144088,-0.4062031478,1.316134037
+58.98123992,-0.1129252111,-0.3105435768,0.55851376,0.6489430148
+58.99127992,0.7994906002,-0.44563582,-0.1092745203,0.9218011849
+59.00132092,0.2725419375,-1.626468961,0.09982191145,1.652163673
+59.01136192,0.6462084,-1.629063809,0.7824796611,1.919298989
+59.02140192,0.3564507978,-1.008408326,-0.1806777942,1.084706868
+59.03144292,0.2153304224,-0.4928308171,-0.4425009084,0.6964599479
+59.04148292,0.1235799344,-1.174545996,0.8591904527,1.460492564
+59.05152392,0.4441498232,-1.483480565,0.9320888597,1.807421726
+59.06156392,0.589829437,-1.405391731,-0.4375670278,1.585714219
+59.07160492,0.5141815962,-1.069229602,-0.1793417054,1.199915873
+59.08164492,0.253115331,-0.7792132603,-0.150252977,0.8329565612
+59.09168592,0.1628486835,-1.119533929,-0.5441991913,1.255399805
+59.10172592,0.3625226927,-1.211401288,-0.540165782,1.375025402
+59.11176692,0.3672769175,-1.210787696,-0.1392836004,1.272909698
+59.12180692,0.8340347077,-0.8651608984,-0.3160537004,1.242580869
+59.13184792,0.4045518941,-1.173054956,-0.08715099514,1.243911355
+59.14188804,-0.06954526178,-1.152309619,-0.2149693751,1.17425118
+59.15192904,0.7512547986,-0.8375013757,-0.004645612836,1.125083956
+59.16196904,-0.2066890051,-1.117644328,-0.8211671788,1.402199959
+59.17201004,0.183864545,-1.108090416,0.5525981319,1.25181278
+59.18205004,0.9877930905,-1.374023319,0.2900908935,1.716923993
+59.19209104,-0.4882910389,-1.093014906,0.4217245817,1.269236521
+59.20213104,0.3319975957,-0.7580651969,0.5200121838,0.9773934303
+59.21217204,0.3146946979,-1.09157671,-0.1054469329,1.140916965
+59.22221204,-0.0698068927,-1.135679846,0.3872347802,1.201912014
+59.23225304,0.2329225382,-0.5506998699,0.4523715931,0.7497755089
+59.24229304,0.03266541771,0.0554329931,-0.2412198651,0.249653499
+59.25233404,0.6306943481,-0.1855021491,0.1025133848,0.6653535918
+59.26237404,-0.01786130008,-1.017979634,0.2158862185,1.040772992
+59.27241504,0.06159516811,-0.4784292711,-0.07614068806,0.4883502192
+59.28245504,0.2012245628,-0.1945419811,-0.7312902117,0.7830218904
+59.29249604,-0.2828527166,-0.2174617143,0.3513545108,0.5007446941
+59.30253604,0.6007432285,-0.3363406517,0.6204240793,0.9267920472
+59.31257704,0.2105520778,-0.6637433957,-0.284178189,0.7520935553
+59.32261704,0.506413826,-0.4102883415,0.1497530401,0.6687431939
+59.33265804,0.8344061521,-0.834698659,-0.3394431478,1.228078633
+59.34269904,0.2064417958,-0.04616519284,-0.7877643746,0.8156728204
+59.35273904,0.2802597871,0.009352913797,-0.7750279695,0.8241974149
+59.36277904,0.1698744786,-0.0758011841,-0.899581849,0.9186134448
+59.37282004,-0.01408416779,0.02500294995,0.8178038603,0.8183071949
+59.38286104,0.3179632914,0.2708094441,-0.1292667353,0.437205099
+59.39290104,0.4102691919,0.1267018907,-0.317887972,0.5342536305
+59.40294204,0.1650124091,-0.1582780978,0.4043624443,0.4645320632
+59.41298204,0.1348359341,-0.06392066516,0.2805733806,0.3177860955
+59.42302304,-0.3928310041,-0.1234395829,-0.3181458342,0.5203559361
+59.43306304,0.6905410389,0.4526760503,-0.04226016641,0.8267698922
+59.44310404,-0.199729174,0.167222949,-0.6459214479,0.6964695072
+59.45314404,0.2602354307,0.0821788884,0.1447484082,0.3089141478
+59.46318504,0.7758599552,0.5497908837,0.8680776358,1.287550957
+59.47322504,-0.6813957743,0.3979155601,-0.2652530909,0.832463931
+59.48326604,0.364552517,-0.3058261163,0.01200901151,0.4759961843
+59.49330604,-0.1344105583,-0.04178095054,0.627724328,0.6433114938
+59.50334704,-0.01078771773,0.6472940087,0.01949110866,0.6476772436
+59.51338704,0.6010050741,0.5859157129,0.9530786097,1.269985495
+59.52342804,-0.01039516171,-0.1853255998,-0.08327779949,0.2034424469
+59.53346804,0.3745934289,0.2900810994,0.12560287,0.4901462661
+59.54350904,0.4542850213,0.5874811952,-0.962721253,1.215870571
+59.55354904,0.215470847,0.194277358,-0.1141896898,0.3117862457
+59.56359004,0.4999308353,-0.1930522202,1.192212773,1.30712329
+59.57363004,0.08448278273,0.3490420466,0.1104153121,0.3757116341
+59.58367104,0.2782709115,0.7303970495,-0.7400709754,1.076391935
+59.59371104,0.5203049466,0.1542556885,0.4841026783,0.7272327399
+59.60375204,-0.03842537966,-0.3321061712,0.4886383635,0.5920628928
+59.61379204,0.3543318399,0.06576783713,0.01889703155,0.3608788702
+59.62383304,0.2897626637,0.3783469759,-0.1334539264,0.4948927014
+59.63387304,0.2662308184,-0.4500050422,-0.444005397,0.6859476505
+59.64391404,0.5972262745,-0.5279070944,0.6235260272,1.01200288
+59.65395404,0.5629726639,0.4296214292,-0.4762978148,0.8534473628
+59.66399504,0.1454719555,0.5781357732,-1.214965459,1.353345531
+59.67403504,0.2202357795,-0.02305114936,-0.1561235815,0.2709422942
+59.68407604,0.004218064884,-0.1564619526,-0.4264035237,0.4542225222
+59.69411604,0.05848486051,-0.08298806995,-0.09115692258,0.1364444326
+59.70415704,1.072979714,0.1354276175,0.5993244016,1.236452928
+59.71419704,0.2288429358,0.1475681183,-0.1957940161,0.3353814777
+59.72423804,0.2468847024,0.5547765121,-0.419245947,0.7378998568
+59.73427904,0.6346472852,0.6460116412,-0.1891030473,0.9251314391
+59.74431904,-0.1215780944,-0.221938708,-0.7461286908,0.7878743849
+59.75436004,0.3915239321,-0.2288611901,0.5632277852,0.7231140794
+59.76440004,0.1950263315,0.2972990121,0.3556375962,0.5028917104
+59.77444104,-0.08325991066,0.7223965967,-0.1146095198,0.7361551451
+59.78448104,0.7888904753,-0.2166050606,1.086425532,1.359994989
+59.79452204,-0.4631429683,-0.7864893892,1.165829551,1.480616598
+59.80456204,0.2472825689,0.551187418,0.751960119,0.9645725785
+59.81460304,0.006241395075,1.079266494,-0.3767273337,1.143144174
+59.82464304,0.3278619332,-0.5175256919,0.7241028142,0.9484994331
+59.83468404,0.2465795326,-0.5642928556,1.211148396,1.358715691
+59.84472404,0.1216552777,0.2580364938,-0.5397558922,0.6105073807
+59.85476504,0.1869376223,0.2218508901,-0.1500489092,0.3266162385
+59.86480504,0.7298281154,-0.4766267207,0.07008531153,0.8744907431
+59.87484604,-0.1931763821,-0.2030065566,-0.4259047562,0.5098270667
+59.88488604,0.1849715326,0.4309172818,-0.06317916512,0.4731762658
+59.89492704,0.4852322142,0.1144316183,0.401916554,0.640376306
+59.90496704,0.0112688408,-0.1262356484,0.282687149,0.3097974337
+59.91500804,1.026192487,0.4005909171,-0.6985019499,1.304396058
+59.92504804,0.1974435522,0.1536180862,-0.9043590242,0.9383217557
+59.93508904,-0.01291468811,0.1966766899,0.2061950433,0.2852453425
+59.94512904,0.7055753267,0.5886520271,-0.8702492917,1.265575592
+59.95517004,-0.08060558539,0.7462906587,-1.649105433,1.811903899
+59.96521004,1.061723092,0.08426159352,0.5833778751,1.214366372
+59.97525104,-0.04906666347,-0.05209408678,-0.02313450873,0.07520995171
+59.98529104,0.5337291304,-0.1494431742,-0.5754584062,0.7989696016
+59.99533204,0.1128856419,0.170770674,-0.1013240612,0.2284126893
+60.00537204,0.004839132833,0.2683818263,-0.06157235026,0.2753967615
+60.01541304,0.07804488866,-0.1039390822,0.3367031425,0.3609201347
+60.02545304,0.466366246,-0.1848654604,0.8379299766,0.97662652
+60.03549404,0.4228988488,0.2853752603,-0.2731146723,0.5786830736
+60.04553404,0.5167804642,0.1211691822,-0.669283998,0.8542160669
+60.05557504,-0.5569315034,-0.6936361894,0.7028218728,1.13369416
+60.06561504,0.2093601229,-0.09185570139,0.4239821917,0.4816949551
+60.07565604,0.2032760219,0.02369163875,-0.2668552279,0.3362947331
+60.08569604,0.1858488707,-0.6027777672,0.4830940336,0.7945191531
+60.09573704,0.657189471,-0.5975703831,0.6804597813,1.11893426
+60.10577704,-0.03521762913,-0.0955581218,-0.1644108403,0.1933974158
+60.11581804,0.304039865,0.7060385723,-0.3325212139,0.8375566028
+60.12585904,0.4711440059,0.4283792979,-0.3997501606,0.7518548317
+60.13589829,-0.1372831675,-0.4470926537,-0.07544428468,0.4737408038
+60.14593829,0.7457683562,-0.316726715,0.6211666757,1.020947742
+60.15597929,-0.2184073369,-0.1886381936,0.7346278024,0.7892807745
+60.16602029,0.3850786925,0.9190137546,0.1852146488,1.013497088
+60.17606029,-0.05291451966,0.6198428661,-0.4698454124,0.7795895308
+60.18610129,0.1102627363,-0.450503627,0.2539048147,0.5287523464
+60.19614129,0.4739640449,-0.5046229335,1.232025295,1.413213554
+60.20618229,0.1625719458,-0.05035318796,0.1631145126,0.2357359228
+60.21622229,-0.02775489174,1.045258795,0.08035769999,1.048710466
+60.22626329,0.4478129211,0.5008356188,0.06855041742,0.6753309478
+60.23630329,-0.176175091,-0.2153372381,0.08424726784,0.2906981096
+60.24634429,0.4308583711,-0.328838674,-0.4246832728,0.6885707601
+60.25638429,0.09414590045,0.2223368669,-0.2439908606,0.343261814
+60.26642529,0.1432230706,0.4205601818,-0.168430801,0.4751343486
+60.27646529,0.6542383081,0.2020347859,-1.172571391,1.357854736
+60.28650629,-0.2826178961,-0.5344652949,0.1864946043,0.6326976087
+60.29654629,0.7886018421,-0.6456646089,0.5761577332,1.170783236
+60.30658729,-0.1724253081,0.450853327,-0.2209598476,0.5308695354
+60.31662729,-0.3796401972,1.105667111,-1.253509719,1.714034147
+60.32666829,1.296078765,0.1828718157,0.08463844657,1.31165008
+60.33670829,-0.3846853576,-0.5492576176,-0.1064356971,0.6789663559
+60.34674929,0.315417231,0.5088381547,0.5806928337,0.8340314529
+60.35678929,0.1756272982,1.075471943,-0.09517980695,1.093866557
+60.36683029,-0.09598279411,0.05974944424,0.1296719474,0.1720392594
+60.37687029,0.07871301527,-0.1171814542,0.7112108731,0.7250849178
+60.38691129,-0.1424298776,0.2181462405,-0.1761555576,0.3144913874
+60.39695129,0.5733868108,-0.1693238536,0.4899089634,0.7729513534
+60.40699229,0.5076750338,-0.04216894984,0.834888255,0.9780340274
+60.41703229,0.1288818058,0.6473066533,-0.9274917787,1.138357335
+60.42707329,-0.1067493637,0.2569524566,-1.278319455,1.308250978
+60.43711329,0.2858840411,-0.6054726392,0.490145191,0.8298006448
+60.44715429,0.03647598191,0.4011639808,-0.3606293643,0.5406630883
+60.45719429,0.1699408627,0.9807523119,-1.137721401,1.511676215
+60.46723529,0.8256212222,-0.8486920694,0.2055284607,1.201736485
+60.47727529,0.03941765672,-0.7385494568,1.159980581,1.375704911
+60.48731629,0.4165547295,0.4519284107,-0.2594269252,0.6671277693
+60.49735629,-0.4661249021,0.8102253572,-0.7322392148,1.187397078
+60.50739729,0.389597165,-0.5740278849,0.7417023486,1.015586696
+60.51743729,-0.6223835544,-0.4718101134,0.5111074591,0.933379294
+60.52747829,0.8712692653,-0.06586866505,0.3324136251,0.9348516631
+60.53751929,0.6645583514,-0.107929076,-0.492112779,0.8339433285
+60.54755929,-0.3423673403,0.4293310053,0.6376488072,0.8415084724
+60.55760029,0.4782107314,0.2383080613,-0.7224813813,0.8985853227
+60.56764029,-0.3862292418,-0.5426748588,0.1971225035,0.6946411383
+60.57768129,0.2946554128,-0.3661227137,1.564737128,1.633790052
+60.58772129,-0.4046860877,0.1507304753,0.4015464252,0.589686389
+60.59776229,0.8221394976,0.1914978475,-0.4356596661,0.9499390106
+60.60780229,-0.1509802976,-0.3388200904,1.01333826,1.079096165
+60.61784329,0.2167794904,0.3945396702,0.4361695433,0.626816376
+60.62788329,0.0341097188,0.5680407746,0.197127766,0.6022401105
+60.63792429,0.07042027019,0.4695210381,-0.1716385835,0.5048453456
+60.64796429,-0.1358976423,0.3846065664,-0.6384668326,0.7576478578
+60.65800529,0.4450455435,0.425569528,-0.9051682788,1.094762336
+60.66804529,0.2451032385,-0.2613152104,0.3332907075,0.4893300853
+60.67808629,0.4671293076,-0.111635626,0.3810887718,0.6131076211
+60.68812629,0.5465011305,0.5893926866,-1.20039829,1.44464642
+60.69816729,0.09500250841,0.4184914735,-1.591550705,1.648391409
+60.70820729,0.005596392942,-0.5102357854,0.7858780628,0.9370038452
+60.71824829,0.3049845375,-0.8864446172,0.5591025746,1.091510566
+60.72828829,0.2780970848,-0.01720364135,-0.5756841087,0.6395671559
+60.73832929,0.4331873171,0.07348740432,-1.502649053,1.565568851
+60.74836929,0.5196568923,-0.1160508585,0.2477781022,0.5872861955
+60.75841029,0.3077292388,0.1003731577,-0.5086165452,0.6028787981
+60.76845029,-0.4445316829,0.521624517,-0.7739912581,1.033809954
+60.77849129,0.5885455346,-0.06962122533,0.709732697,0.9246369355
+60.78853129,-0.5200944468,-0.7929716125,0.529774695,1.086261221
+60.79857229,0.7118658344,-0.3877114744,1.290588083,1.524037649
+60.80861229,0.1352131618,0.6291908828,0.1912600851,0.6713748478
+60.81865329,-0.6109106594,0.825871483,-1.307115238,1.6624758
+60.82869329,0.6961775355,-0.1116113966,1.046840467,1.262139148
+60.83873429,-0.1796177488,-0.702779042,-0.4353550261,0.8459875391
+60.84877429,-0.5864365901,-0.1193963064,1.114739504,1.265230222
+60.85881529,1.001291169,0.5253251101,0.3145082814,1.173654947
+60.86885529,-0.9319564202,-0.2399531754,-1.208258702,1.544671288
+60.87889629,0.98754071,-1.034410748,0.6354385597,1.564935913
+60.88893629,0.3639402405,-0.4948741632,-0.1222418904,0.626335386
+60.89897729,0.215881888,0.4377261452,-0.5352816027,0.7243863347
+60.90901729,-0.1698090263,0.1737631693,0.4262006253,0.490587115
+60.91905829,-0.1895624374,-0.2835417196,0.2637860245,0.4311761718
+60.92909829,0.6819009738,-0.2343674034,0.08268021405,0.7257775386
+60.93913929,0.05030048536,-0.3603409503,-0.007030107379,0.3639026817
+60.94917929,0.5909603982,0.337918267,0.6033695054,0.9096580168
+60.95922029,-0.4132700926,0.5079569427,-1.045351181,1.23351997
+60.96926029,0.6234711365,0.2432916432,0.3498658097,0.7551908146
+60.97930129,-0.4408830203,-0.0158706589,0.6503255707,0.785845445
+60.98934229,-0.6597528172,-0.2965865654,1.217420704,1.416104001
+60.99938229,0.7578321122,-0.3384161209,1.385127035,1.614748242
+61.00942229,-0.3538686673,-0.006600227393,0.3994882053,0.5337203602
+61.01946329,-0.1918278863,0.7719053371,-0.3583197141,0.8723696492
+61.02950429,0.4183769411,0.1454997389,0.4267607886,0.6150887818
+61.03954429,-0.4253145894,-0.7207433695,1.239663513,1.495703557
+61.04958529,-0.1614183632,-0.2706304462,0.8647441381,0.9203690297
+61.05962529,-0.232235399,0.3818595079,0.1514060479,0.4718832013
+61.06966629,0.3399693606,0.06036186699,-0.570758999,0.6670746256
+61.07970629,0.4473775593,-0.2015474571,-0.2454450631,0.5486450009
+61.08974729,0.7015980506,-0.3255152994,-0.6607692826,1.017259101
+61.09978729,0.4186155806,-0.4673954656,-1.511355557,1.636426945
+61.10982829,0.2174292988,0.07368880436,-1.064509583,1.088984018
+61.11986829,0.947358571,0.9715898712,-1.914622234,2.346753808
+61.12990929,0.01478426908,0.1338084504,-2.698017569,2.701374109
+61.13995033,0.2781739026,-0.4772456485,0.4023726368,0.6834090049
+61.14999133,0.580665571,-0.1548718754,0.02355141521,0.6014253672
+61.16003133,-0.6278284085,0.07653804291,-0.9072411168,1.105944405
+61.17007233,1.340894018,-0.006458249688,1.267027897,1.84483012
+61.18011233,-0.8998277975,0.3186925489,0.450080654,1.055380311
+61.19015333,-0.2017484734,0.3357613754,-0.1377791119,0.415236356
+61.20019333,0.3401720032,-0.3775628277,0.2130035412,0.5510364681
+61.21023433,-0.4556329507,-0.2420831699,-0.3615906465,0.6300424133
+61.22027433,0.6252994877,0.4000794685,-0.0782836926,0.7464525216
+61.23031533,0.4807240475,-0.2695076711,0.1375551635,0.5680241347
+61.24035533,-0.4610632234,0.03369841743,0.2607033724,0.5307364013
+61.25039633,0.491401648,0.4654567481,-1.50558494,1.650730619
+61.26043633,-0.05368441524,-0.1198008606,-2.10307624,2.10716965
+61.27047733,-0.1069784557,-0.6862748373,0.3434613544,0.7748440128
+61.28051733,0.9622925059,0.4556764759,0.4217503095,1.145216679
+61.29055833,-0.322279231,0.6090695539,-1.824741173,1.95051531
+61.30059833,0.7417181361,-0.1429788946,1.325457954,1.525590884
+61.31063933,-0.2515512191,0.06943934038,0.06469768703,0.2688598678
+61.32067933,-0.4682380128,0.5063080279,-0.528197701,0.8686699414
+61.33072033,0.4587788989,0.1682801256,1.947178946,2.007561238
+61.34076033,-0.3444778197,0.1965757158,1.120264539,1.188402127
+61.35080133,-0.4356100013,0.1310811629,0.7197331899,0.8514424286
+61.36084133,0.7272557791,-0.02371937647,2.726461934,2.821889129
+61.37088233,-1.098064049,-0.4519554541,1.180719486,1.674546773
+61.38092233,-0.3492276592,0.2002074945,3.370975957,3.394925905
+61.39096333,-0.2862134586,0.5014611978,0.2847406912,0.6437846985
+61.40100333,-0.9959299296,-0.02271416701,1.732318913,1.998329596
+61.41104433,0.2509080071,-0.3038861563,2.657503381,2.686563947
+61.42108433,-1.498368745,-0.4714989684,1.172449769,1.960116995
+61.43112533,0.1975159115,-0.2554316689,2.308143355,2.330618721
+61.44116533,-0.08004447196,0.01686680518,0.4340674692,0.4417082459
+61.45120633,-0.2118196811,0.1841548776,-0.7326666462,0.7845897085
+61.46124633,0.8671123336,-0.8245818065,-0.006261198521,1.196602757
+61.47128733,0.3835295458,-0.6273618007,0.5105379403,0.8951685483
+61.48132733,0.5014751215,-0.366687774,-0.9457204735,1.131514222
+61.49136833,-0.4703633295,1.145332283,-1.388136597,1.860094329
+61.50140833,1.124982949,0.7200295707,-1.359219777,1.905651495
+61.51144933,-0.3025069809,-0.3659038086,-1.945677965,2.002762796
+61.52149033,0.2697010678,-0.6004088774,-0.3342940897,0.7382289783
+61.53153033,1.043533574,-0.1042461706,-0.5846613389,1.200690828
+61.54157133,-0.3660593445,0.4294282883,-0.9839595097,1.134277045
+61.55161133,1.078830438,0.6057203785,-1.801024282,2.185053948
+61.56165233,-0.6685816743,0.2787414479,-2.241755823,2.35587933
+61.57169233,0.774132176,0.1109418538,-1.107321142,1.355635951
+61.58173333,0.2159772889,-0.1742445414,-0.7472197813,0.7970851592
+61.59177333,-0.7939772605,0.4724886462,0.3991245085,1.006452077
+61.60181433,0.4753345592,0.87375594,-0.1712748867,1.009320302
+61.61185433,-0.331624653,0.08547397714,-1.224040337,1.271045026
+61.62189533,0.4731589564,0.07331732344,0.1453863394,0.5003918621
+61.63193533,0.2894492712,-0.4072975273,-0.2319309783,0.5508757891
+61.64197633,-0.7681123213,-0.06558050696,-0.4236681962,0.879654524
+61.65201633,0.002501292676,0.978953416,-1.079124114,1.457005457
+61.66205733,0.08011334119,0.1964594658,-0.9087695789,0.9332077029
+61.67209733,-0.2849248054,-0.2074300484,-0.5663525373,0.6670566439
+61.68213833,-0.2267367139,0.2925158069,-0.8648721921,0.9407331946
+61.69217833,-0.2049867893,0.7285829508,-1.155926122,1.381672139
+61.70221933,0.3217149016,0.4128210995,-0.4977705449,0.7222861299
+61.71225933,-0.9679801657,0.05520798493,-0.8097920054,1.263248437
+61.72230033,-0.6913763136,-0.1716358427,1.256960161,1.444786807
+61.73234033,0.2865734827,-0.7036695729,-0.26506598,0.8046957205
+61.74238133,-1.223668966,0.8993270566,0.3131528968,1.55055462
+61.75242133,0.2045807733,0.4764059152,-0.3567222548,0.6293382683
+61.76246233,-0.7914610574,-0.5693270159,1.210257865,1.554113238
+61.77250233,-0.9815528689,-0.6437261838,1.462952306,1.875648924
+61.78254333,-0.742309655,0.7984920419,0.8229529184,1.36596657
+61.79258333,-0.03645454821,0.8789269982,-0.4455940855,0.9861012581
+61.80262433,-0.7784532684,-0.2734161694,0.9143191713,1.231554075
+61.81266433,-0.7195593084,0.1588653409,0.9580961055,1.20869845
+61.82270533,-0.2940850169,-0.03012978863,0.3665870923,0.4709351309
+61.83274533,-1.412796206,0.08370906819,1.05192696,1.763391805
+61.84278633,-0.6885124205,0.8065663889,1.470995736,1.813402092
+61.85282633,-0.7556424031,0.4481992758,-0.7595585757,1.161381618
+61.86286733,-1.121358333,0.4793731945,0.7503603208,1.431881204
+61.87290733,-0.4601262802,0.5604996206,-0.6947071069,1.004238011
+61.88294833,-1.208291008,0.5137336629,-0.5028096753,1.405954127
+61.89298833,-0.01381930034,0.3622661826,0.6632455784,0.7558587549
+61.90302933,-1.376501661,0.9392391273,-0.9498965549,1.918132015
+61.91306933,-0.1931670083,1.109954289,-0.2115996248,1.146336085
+61.92311033,-0.6483632451,0.02928588923,0.2442569089,0.6934652107
+61.93315033,-1.833094652,0.7311378186,0.9412795132,2.186505347
+61.94319133,0.2676346983,1.285373098,-1.278704787,1.83272973
+61.95323133,-1.086523254,0.7111570787,-1.445532866,1.943152706
+61.96327233,-0.9440591334,0.1509687493,1.168437994,1.509730624
+61.97331233,-0.3054728348,1.120624581,-0.7879321897,1.403549158
+61.98335333,-2.125371381,0.4093740563,-3.872410952,4.436254862
+61.99339333,-1.41330199,1.475833576,2.779370465,3.449696717
+62.00343433,-1.056040257,0.9857639605,-0.5840058661,1.558208735
+62.01347433,-1.648741444,0.8156661183,-1.084797083,2.135519674
+62.02351533,-0.1882207938,-0.1797965457,1.046831111,1.078707208
+62.03355633,-1.118842642,0.3948449679,0.8531192887,1.461343193
+62.04359633,-0.581588956,1.162038363,-1.119159415,1.714962584
+62.05363733,-1.346838444,1.072985561,-1.402811939,2.22107027
+62.06367733,-1.349162566,1.025583938,1.329164504,2.153773507
+62.07371833,-1.178771705,0.4202443956,-0.3643487781,1.303402515
+62.08375833,-1.588702526,1.353097157,-0.6599383932,2.188690548
+62.09379933,-0.9313570806,1.030297305,-1.691132296,2.188348005
+62.10383933,-1.438342106,1.277461084,0.6570814437,2.032852887
+62.11388033,-1.796360981,0.6921499734,0.5369503981,1.998574515
+62.12392033,-1.905803463,1.141934027,0.4484896266,2.266548722
+62.13396133,-1.607134265,1.617681035,0.3037973517,2.300448936
+62.14400083,-1.02610836,0.8130341403,0.8206239724,1.545104069
+62.15404183,-2.421381849,-0.3595349848,-0.1954449373,2.45571867
+62.16408183,-1.952611009,1.386555218,1.978075633,3.106124327
+62.17412283,-1.334040643,1.261133612,-1.623316289,2.450566913
+62.18416283,-3.195248123,1.304960978,0.7847220683,3.539537038
+62.19420383,-2.482457917,1.237831434,1.233315191,3.035768491
+62.20424383,-1.826434966,0.9067857648,-1.741941676,2.681881039
+62.21428483,-1.945654723,0.9586265941,-1.882776543,2.872174221
+62.22432483,-1.765629039,1.480023252,1.486163998,2.741641508
+62.23436583,-2.222436476,1.130610456,0.4898773885,2.541157954
+62.24440583,-1.969812202,0.9123459553,-2.182471488,3.078265266
+62.25444683,-2.040108452,2.217412256,2.523917892,3.930537003
+62.26448683,-3.501731686,1.35953465,-0.6397654992,3.810480174
+62.27452783,-2.31824442,1.598499828,0.8778436553,2.949587832
+62.28456783,-1.810793225,1.248258335,-0.4353567803,2.242020629
+62.29460883,-2.791430639,0.4406623976,0.7009583652,2.911633733
+62.30464883,-1.716544587,1.490310259,0.9024990249,2.445823885
+62.31468983,-2.095712841,1.243118925,-1.475486398,2.848581592
+62.32472983,-2.982460344,1.06122184,-0.8602312571,3.280435842
+62.33477083,-2.07490494,1.623984918,1.419901012,2.99310481
+62.34481083,-1.716092159,0.6646715681,-1.107113566,2.147664089
+62.35485183,-2.696442036,1.119051899,-0.2388593441,2.929185995
+62.36489183,-1.542908303,1.426256204,0.2065581554,2.111264801
+62.37493283,-2.385129843,0.6354677957,-3.345196168,4.157282897
+62.38497283,-1.859670393,-0.02574119747,1.47111385,2.371331385
+62.39501383,-2.187457701,0.3310722739,-0.4403356844,2.255764961
+62.40505383,-3.346959688,1.493511171,-0.7571302271,3.742453868
+62.41509483,-1.67362924,1.387509776,0.3605744004,2.203686028
+62.42513483,-2.604931065,0.3629203399,-0.3305010009,2.650774969
+62.43517583,-3.309968155,-0.342074541,1.447473557,3.628785455
+62.44521583,-2.259601087,0.4379210402,0.3912085479,2.334655443
+62.45525683,-3.855585004,1.271504379,-1.335203508,4.273760349
+62.46529683,-1.504050485,1.525019916,0.08484309912,2.14360723
+62.47533783,-3.802483515,0.6883447516,-1.309993823,4.080292048
+62.48537783,-4.483389731,-0.03355749954,2.600328721,5.183012546
+62.49541883,-2.317467764,1.257195219,1.503025029,3.03484446
+62.50545883,-3.896721628,1.304666571,-1.695689616,4.445442338
+62.51549983,-2.365946736,0.7762732071,1.855244928,3.105195291
+62.52553983,-3.912363222,0.6308496648,0.3712490773,3.980249133
+62.53558083,-3.127666882,1.787860153,0.2449427873,3.610919692
+62.54562083,-3.211339368,0.9209407045,0.8891223496,3.45707548
+62.55566183,-4.077233361,0.3854262364,0.4300200266,4.117924537
+62.56570183,-2.255741632,0.5130952931,0.8135289609,2.452237032
+62.57574283,-2.763749336,0.2900902722,0.5103911752,2.825413582
+62.58578283,-2.486525533,0.08447870795,0.9151880676,2.650946072
+62.59582383,-3.059169966,0.9101179469,0.6270957524,3.252704205
+62.60586383,-2.947407748,1.004520586,-1.850009916,3.621989885
+62.61590483,-3.123266267,0.4146979827,0.4135805798,3.17770601
+62.62594483,-2.754199371,0.1528435494,-1.448444195,3.115600409
+62.63598583,-3.620208846,-0.07674148947,-1.627303505,3.969876326
+62.64602583,-2.518762694,0.5835179524,-0.9291716838,2.74736578
+62.65606683,-2.58548878,1.103537336,-2.141304751,3.533798653
+62.66610683,-3.307613482,1.326718614,-2.466642076,4.334144939
+62.67614783,-2.884379149,0.9203282087,-1.943361298,3.597679839
+62.68618883,-4.144172578,-0.01728148241,-0.2778035545,4.153509338
+62.69622883,-4.021750886,0.9800237489,0.4813977563,4.167333745
+62.70626983,-3.485020636,1.530141492,-1.162296664,3.979652667
+62.71630983,-3.494632581,1.252894154,1.220255435,3.907841343
+62.72635083,-4.303206612,1.328785166,0.8654089665,4.586086549
+62.73639083,-3.599822237,0.9332266548,0.3790966254,3.73809395
+62.74643183,-3.262400179,1.003800282,1.926602009,3.919523598
+62.75647183,-4.051441585,1.815246757,-0.09982425034,4.440637858
+62.76651283,-3.660794663,1.332927333,0.1348297763,3.898242156
+62.77655283,-3.402358548,0.4342386465,2.529895501,4.262039199
+62.78659383,-3.738604731,0.3798524512,1.915481774,4.217881417
+62.79663383,-4.03842773,1.44335624,0.2162434834,4.294058338
+62.80667483,-3.608438694,0.886340683,0.9053436953,3.82440542
+62.81671483,-3.685992946,-0.4600412763,1.385587211,3.96459757
+62.82675583,-3.303259937,-0.1757066377,0.7310574925,3.387749119
+62.83679583,-3.177691566,0.4062058156,-0.7761558974,3.296231914
+62.84683683,-2.620362452,1.114225388,-0.2597730803,2.859244594
+62.85687683,-2.639410341,0.5618209086,-1.611539996,3.143118013
+62.86691783,-4.324210395,0.05891252495,-1.826046857,4.694327784
+62.87695783,-2.938066821,0.1497741997,-1.334719359,3.23050224
+62.88699883,-2.371348833,0.1958308901,-2.566222497,3.499591823
+62.89703883,-2.666813025,0.6842878803,-3.014506887,4.082571908
+62.90707983,-2.757422356,0.00005405019969,-1.824598501,3.306438831
+62.91711983,-3.193657096,-0.2433135337,-0.1194141769,3.205137574
+62.92716083,-2.787111593,0.6551102742,-0.7069464988,2.949056435
+62.93720083,-3.46657384,-0.3188293006,-1.658582016,3.856122484
+62.94724183,-2.967604616,-0.4765309726,0.716328941,3.089803566
+62.95728183,-2.8325161,-0.6452963074,-0.329561938,2.923724654
+62.96732283,-4.258097974,-0.4007615462,-0.2289336956,4.283038502
+62.97736283,-2.924150448,0.2922908719,0.4790313882,2.977509171
+62.98740383,-2.945580493,0.2248402791,-0.5679763091,3.008254424
+62.99744383,-4.223828613,0.04601437122,-1.138168128,4.374731096
+63.00748483,-3.051616533,-0.9695778443,0.5111448812,3.242485736
+63.01752483,-3.460440695,-0.3124327391,-0.1399934524,3.477335501
+63.02756583,-4.298073049,0.6030689585,0.02082427382,4.340225541
+63.03760583,-2.928905404,-0.3791189545,0.3538348997,2.974460822
+63.04764683,-3.694015911,-0.4862268256,0.6852492356,3.788368592
+63.05768683,-2.822747157,-0.1103413082,-0.4804142547,2.865462366
+63.06772783,-2.785986589,-1.069465318,-0.8341392267,3.098590904
+63.07776783,-3.0223749,-1.284154392,0.2776024103,3.295582746
+63.08780883,-1.887467179,-0.9497686471,0.6290048683,2.204595192
+63.09784883,-3.19692452,-0.9558234389,-0.7855488646,3.427974891
+63.10788983,-2.468650887,-1.442848263,-0.09388464868,2.860919894
+63.11792983,-1.916928375,-1.386245023,0.05948606372,2.366395625
+63.12797083,-3.433245295,-1.123315177,-0.6687302667,3.673718881
+63.13801092,-1.950047005,-1.361482649,-1.541734766,2.834301398
+63.14805192,-2.019428312,-2.557462783,0.6293071693,3.318845297
+63.15809192,-3.486677444,-1.786313272,0.2412841845,3.925054492
+63.16813292,-2.425425637,-1.057835425,-0.3977422267,2.675799729
+63.17817292,-2.20203364,-1.206279712,-0.776616658,2.628154548
+63.18821392,-2.263121695,-2.074947332,1.379446465,3.366006356
+63.19825392,-2.551838347,-2.306935028,0.04878975213,3.440379138
+63.20829492,-2.366678808,-1.398886703,-0.5108186066,2.796245382
+63.21833492,-2.283797596,-1.202403739,-0.2096624422,2.589491176
+63.22837592,-2.667338982,-1.766727,0.7143408877,3.278155646
+63.23841592,-2.236936986,-2.218300594,0.998703264,3.304868048
+63.24845692,-2.210344873,-2.046153011,0.7446774119,3.102726389
+63.25849692,-2.064392961,-1.782678351,0.40150491,2.756966919
+63.26853792,-1.957261299,-1.846219751,-0.2876110893,2.705941481
+63.27857792,-2.091225396,-1.407756929,0.05999009371,2.521626863
+63.28861892,-2.120888759,-1.63538041,0.2831128263,2.693100645
+63.29865892,-1.996966379,-1.884452355,0.3188697195,2.76418402
+63.30869992,-2.224329951,-2.002705567,0.8517685819,3.11190987
+63.31873992,-2.085614115,-1.728285358,0.6997251874,2.797565344
+63.32878092,-1.198543188,-2.252913334,0.8669748509,2.695138151
+63.33882092,-1.875746289,-2.513645211,0.9094104338,3.265557185
+63.34886192,-1.867342963,-2.125380152,0.1763298047,2.834660955
+63.35890192,-0.9564534764,-2.070249386,-1.156372265,2.556938128
+63.36894292,-2.31692295,-3.085356429,-0.9729971498,3.979231044
+63.37898292,-1.61781552,-3.193732232,0.5204665124,3.617753173
+63.38902392,-1.324302252,-2.553922879,0.08476591587,2.8781042
+63.39906392,-2.326485925,-2.404483688,-1.171510121,3.544928001
+63.40910492,-1.498050949,-2.990594698,0.3483396864,3.362908538
+63.41914492,-1.425699695,-2.844772156,-0.2205470341,3.189669142
+63.42918592,-2.585772078,-2.840930828,-0.8603704208,3.936666416
+63.43922592,-1.404557772,-2.731000543,-0.1881955594,3.076778196
+63.44926692,-1.831624954,-2.82562194,-1.324821777,3.618582881
+63.45930792,-1.411725142,-3.57453069,-0.1018877327,3.844557015
+63.46934792,-1.630399752,-3.53864048,-0.8864221054,3.995738223
+63.47938792,-2.278914294,-3.831894425,1.006509882,4.570550009
+63.48942892,-1.638083139,-2.797042797,-1.021135522,3.398452962
+63.49946992,-2.391915683,-2.326726537,-1.536917245,3.673830649
+63.50950992,-1.832181901,-3.67819276,0.2306492686,4.115724916
+63.51955092,-1.825373257,-3.942137829,0.7480401456,4.408174481
+63.52959092,-1.905943504,-3.821228811,-0.1136499918,4.271688962
+63.53963192,-1.680965596,-3.147687748,-0.6101019895,3.62019446
+63.54967192,-1.707844954,-3.908499674,0.7304183918,4.327425923
+63.55971292,-1.983846396,-4.125931897,0.6160936314,4.619364881
+63.56975292,-1.805392152,-3.845599422,-1.142085178,4.399140176
+63.57979392,-1.838611646,-3.595075467,-0.8260402483,4.121577718
+63.58983392,-2.363620422,-3.886046366,-0.3378515357,4.560943052
+63.59987492,-1.385768329,-3.720066426,0.164127835,3.973183361
+63.60991492,-2.291580532,-3.25949996,-1.234501006,4.171291653
+63.61995592,-2.392291659,-3.508819681,-0.5957149154,4.288327319
+63.62999592,-2.482688005,-3.987025734,0.3388788915,4.709028864
+63.64003692,-2.398767889,-4.106573812,0.6200913727,4.796097285
+63.65007692,-2.039846789,-3.542749319,0.2356310964,4.0948223
+63.66011792,-2.308793566,-3.860489064,0.8474749714,4.57734829
+63.67015792,-2.07151487,-4.17183137,0.4851464063,4.683024437
+63.68019892,-2.573774469,-3.551192991,-0.3655954045,4.40101655
+63.69023892,-1.926074444,-2.618190503,-0.5833158946,3.302263119
+63.70027992,-3.866918662,-3.541852941,1.063898549,5.350669333
+63.71031992,-3.091710598,-5.241325997,1.664356726,6.308744403
+63.72036092,-1.468223425,-3.670251657,-1.431597197,4.204271374
+63.73040092,-3.411480497,-3.112650062,-0.002341809869,4.618094312
+63.74044192,-3.104872389,-4.630372653,1.19429789,5.701484974
+63.75048192,-2.48395305,-4.546894879,0.7779141551,5.239220002
+63.76052292,-2.029489177,-2.291121964,0.2209230101,3.068692417
+63.77056292,-2.508249108,-1.627274854,-1.136166626,3.198470203
+63.78060392,-2.655851835,-4.403877246,1.237739779,5.289582548
+63.79064392,-3.003144577,-4.679904417,0.3084874034,5.569160366
+63.80068492,-2.421371324,-3.195271512,-0.8810672253,4.104762914
+63.81072492,-2.710249944,-2.563742108,-1.57176782,4.048293768
+63.82076592,-2.966897687,-3.136620723,-0.8421867496,4.398880536
+63.83080592,-1.767024039,-3.805173819,0.1897895104,4.199731159
+63.84084692,-2.705953117,-3.630202615,-0.6134091747,4.569116338
+63.85088692,-2.543965071,-3.827489718,-1.342817752,4.78796359
+63.86092792,-1.885748683,-4.106977855,0.3967476153,4.53659827
+63.87096792,-2.334407879,-3.379480147,-0.195678826,4.112011237
+63.88100892,-2.247612394,-3.529351009,-0.727601788,4.247055966
+63.89104892,-2.106315013,-3.552134977,-0.7613273585,4.199267219
+63.90108992,-2.54335316,-3.906078342,0.1372095931,4.663144839
+63.91112992,-2.444178535,-4.453031572,-0.6339036655,5.11911445
+63.92117092,-3.170206253,-3.929378035,0.65709957,5.091365168
+63.93121092,-1.173439775,-3.107592221,-0.2939284211,3.334739006
+63.94125192,-1.753536705,-3.90060798,-0.3530051798,4.291182383
+63.95129192,-3.100291972,-4.605448604,1.026420236,5.645839677
+63.96133292,-1.136768085,-4.795106844,0.5154513556,4.954894694
+63.97137292,-2.303715405,-3.064706695,-1.713694362,4.199557138
+63.98141392,-3.004921254,-4.297069666,0.5780288422,5.275270306
+63.99145392,-1.492284279,-4.68795194,0.5804712242,4.953862392
+64.00149492,-2.783402412,-4.364527239,0.2570342445,5.182903975
+64.01153492,-2.136603005,-3.583391853,-1.423953132,4.40833439
+64.02157592,-2.142089886,-3.695944322,0.316648947,4.283552272
+64.03161592,-2.585564794,-4.06796377,-0.7993886393,4.885948909
+64.04165692,-2.762385765,-4.310404826,-0.9550216395,5.207920047
+64.05169692,-2.512071433,-4.400537317,-0.4141793346,5.083972471
+64.06173792,-2.147781566,-3.620677208,1.362634551,4.424821129
+64.07177792,-3.813503762,-3.684888699,-1.607339941,5.54118736
+64.08181892,-2.076512924,-4.222874932,-0.7700297695,4.768388036
+64.09185892,-1.740435141,-4.611534971,0.4485907835,4.949404303
+64.10189992,-3.325084377,-4.449844255,0.3121115077,5.563696038
+64.11193992,-2.526508793,-3.461099384,-3.322739936,5.422458512
+64.12198092,-1.882041986,-4.443776307,-0.4434469879,4.84622277
+64.13202092,-3.520062999,-4.669413927,-0.1672344607,5.849977547
+64.14206183,-2.591702324,-4.477810611,-0.9608290941,5.262214491
+64.15210183,-1.89781412,-4.217075078,-1.528824114,4.870597892
+64.16214283,-1.63649869,-3.36241271,0.5763074219,3.783659265
+64.17218283,-1.954087869,-3.331629458,-2.104887707,4.398723281
+64.18222383,-3.888618557,-5.837658963,1.96024221,7.283005284
+64.19226383,-1.389763439,-3.931329251,-0.1976247793,4.174427823
+64.20230483,-2.883162343,-3.728480861,-0.5974421829,4.750908523
+64.21234483,-2.340777835,-4.15633391,-0.7893606645,4.835022513
+64.22238583,-2.898516254,-4.703697322,1.659752043,5.76896367
+64.23242583,-2.056882651,-4.025722023,-1.386222219,4.72851098
+64.24246683,-2.920133118,-4.078399004,-1.40461639,5.208979081
+64.25250683,-2.115580218,-4.196340852,-0.1639693755,4.70232306
+64.26254783,-2.167097404,-4.148738669,-0.1508499777,4.683065173
+64.27258783,-2.522558999,-4.112739994,-1.077896783,4.943662168
+64.28262883,-2.908513239,-3.761465005,-0.8602973306,4.83199542
+64.29266883,-2.653843316,-3.966246192,-0.2661377746,4.779625771
+64.30270983,-3.065988697,-3.827377743,0.1179921341,4.905408161
+64.31274983,-2.507960548,-3.905436903,-0.2444837809,4.647803334
+64.32279083,-2.41210685,-4.252438162,0.810771414,4.955687647
+64.33283083,-2.838139075,-4.442292868,0.6603821969,5.31273037
+64.34287183,-2.560606539,-4.171767343,0.8305876279,4.964899236
+64.35291183,-2.270600722,-4.049368163,0.7408217579,4.701258027
+64.36295283,-2.923996081,-4.409982617,0.113748225,5.292507763
+64.37299283,-2.947160411,-4.355775127,0.5500703806,5.287826478
+64.38303383,-3.065853918,-4.148219144,-0.6171519774,5.195003261
+64.39307383,-2.255208658,-4.003549381,0.2832870734,4.603762081
+64.40311483,-2.130788972,-3.865182624,-1.451481823,4.646148711
+64.41315483,-2.204923481,-4.242405217,-1.010307648,4.886758754
+64.42319583,-1.733973675,-4.357966956,-1.211463561,4.844190815
+64.43323583,-1.985168306,-4.741666802,-1.341855301,5.312708622
+64.44327683,-1.856755556,-4.572858563,-1.297708822,5.103197509
+64.45331683,-1.677624935,-4.535303358,-0.5574472278,4.867663648
+64.46335783,-1.796223133,-4.416276267,-0.4037800616,4.784657976
+64.47339783,-1.965603814,-4.401614374,-1.530695223,5.057750025
+64.48343883,-2.460904203,-4.687245304,-0.05919077933,5.294319747
+64.49347883,-1.738433639,-5.411108674,-0.03083353758,5.683590354
+64.50351983,-1.779765121,-5.029307127,0.3814764422,5.34855292
+64.51355983,-2.866497779,-4.354130013,-0.7356189054,5.264636061
+64.52360083,-2.633408175,-6.424410097,1.795683435,7.171635985
+64.53364083,-1.409029576,-4.139402712,-0.2186548752,4.378107938
+64.54368183,-2.419820058,-4.86487436,-0.7751314652,5.488475238
+64.55372183,-2.934805829,-5.73388258,0.256268844,6.446407404
+64.56376283,-1.080325571,-4.829402226,-0.0772452271,4.949363194
+64.57380283,-2.3281708,-5.182695966,-1.383912569,5.847728683
+64.58384383,-2.265474468,-5.30102373,-0.5958616805,5.795539517
+64.59388383,-1.663961308,-4.525932903,-0.3671975416,4.836080015
+64.60392483,-2.247100032,-4.813032946,-1.763366459,5.596803191
+64.61396483,-1.974586746,-4.997994702,-2.114250269,5.774859138
+64.62400583,-2.112881728,-5.618659102,0.03782271445,6.002918445
+64.63404583,-2.684829758,-5.169701114,-0.8531678206,5.887445606
+64.64408683,-2.515322193,-4.80475475,-0.4161258727,5.439271521
+64.65412683,-2.569245215,-5.234546735,-0.4021007413,5.844928187
+64.66416783,-2.660228476,-5.052287854,0.8622906464,5.774597238
+64.67420783,-2.169795894,-5.24990854,0.403730945,5.694958523
+64.68424883,-3.514440024,-5.752098411,-0.8106527156,6.78933595
+64.69428883,-2.657746333,-6.268801655,2.031402825,7.10549697
+64.70432983,-2.416791785,-5.144114867,0.4338137001,5.700087247
+64.71436983,-3.519235618,-4.735875134,-0.1951946765,5.903527216
+64.72441083,-2.794103986,-5.023044174,-0.06631795049,5.748250859
+64.73445083,-2.536820943,-4.886397668,1.382531456,5.676595449
+64.74449183,-2.418412779,-4.088001594,-1.001628626,4.854249407
+64.75453183,-3.364110156,-5.071649739,-0.2627721173,6.091626828
+64.76457283,-2.241869259,-4.543100328,-0.2235618585,5.071066778
+64.77461283,-2.859010711,-4.181718427,0.245390684,5.071580409
+64.78465383,-2.454901744,-4.16769388,-2.58572647,5.484723897
+64.79469383,-2.618623782,-5.3331343,-0.5907278252,5.970634081
+64.80473483,-2.2505667,-4.622506686,-0.4496087837,5.160888159
+64.81477483,-2.898969414,-4.207495,-1.340470095,5.282414023
+64.82481583,-2.193032144,-3.961584791,-2.242482632,5.052946902
+64.83485583,-2.456379628,-4.676672661,-1.266407508,5.432205448
+64.84489683,-2.68177108,-4.902539784,-0.9137215859,5.662303382
+64.85493683,-2.356013048,-5.155506998,-1.004996622,5.7567411
+64.86497783,-2.748435478,-5.55478061,-0.394635601,6.210090375
+64.87501783,-2.162537745,-3.760081261,-2.790439244,5.157647891
+64.88505883,-3.273929134,-3.513384309,-1.391899865,4.999986651
+64.89509883,-2.236805862,-6.390145413,0.8179652435,6.819554678
+64.90513983,-2.48793208,-6.437699064,1.154698792,6.997649932
+64.91517983,-2.162364375,-4.628942132,-2.477268806,5.678008954
+64.92522083,-4.759851058,-4.796173084,0.5116816556,6.776523922
+64.93526083,-2.483125669,-5.972501019,1.052806381,6.553249788
+64.94530183,-2.632488407,-5.974400779,1.258729529,6.64889915
+64.95534183,-3.378730827,-4.968597241,0.3570461905,6.019157958
+64.96538283,-2.365092897,-4.660736659,0.4733543265,5.247875278
+64.97542283,-2.886902222,-5.434600448,-0.03865594268,6.153907763
+64.98546383,-2.755021197,-4.684902032,0.4641829687,5.454714903
+64.99550383,-2.287067066,-3.985881434,0.233540132,4.601354971
+65.00554483,-3.152249746,-3.809477662,-2.273666418,5.442275029
+65.01558483,-2.575440633,-3.529981046,-1.124100312,4.511902276
+65.02562583,-2.57034303,-3.991588317,-0.2896348107,4.756398733
+65.03566583,-2.963697506,-3.875541551,-1.776167768,5.192118755
+65.04570683,-2.823002096,-3.241045855,-1.058927246,4.426629189
+65.05574683,-3.307241891,-4.051716405,-0.8860893989,5.304659195
+65.06578783,-2.476722383,-3.840110348,-1.190935156,4.722174054
+65.07582783,-3.031605899,-4.290472253,-1.292646303,5.410149808
+65.08586883,-2.556536,-3.816400181,-0.5940157145,4.631807566
+65.09590883,-2.380738584,-3.790958653,-1.456032711,4.707368158
+65.10594983,-3.158883704,-3.889229883,-0.6569732702,5.053342381
+65.11598983,-2.363297948,-4.674462413,-0.6619246924,5.279575773
+65.12603083,-2.443762652,-4.379886121,-0.1751369727,5.018570642
+65.13607083,-2.839585091,-3.692918681,0.2215749747,4.66368817
+65.14611167,-2.771200735,-4.782054105,-0.02271584809,5.527034556
+65.15615167,-3.175637147,-4.274545899,-0.9009354794,5.400749825
+65.16619267,-2.977274156,-4.27364689,2.161560091,5.639198628
+65.17623267,-1.654317934,-5.256715869,1.571168481,5.730479905
+65.18627367,-3.103849418,-5.366889106,1.467369293,6.371071537
+65.19631367,-2.037116139,-3.57377903,0.7465198696,4.180793063
+65.20635467,-4.34547818,-2.895129839,-3.749697776,6.428467221
+65.21639467,-2.18284381,-3.598657764,-0.5383741951,4.243228909
+65.22643567,-2.903342546,-4.73491853,-0.1387392247,5.555906767
+65.23647567,-3.254796167,-4.401219102,-0.5518882799,5.50172776
+65.24651667,-1.704124517,-3.576421387,-1.114700913,4.115505854
+65.25655667,-3.291894996,-4.084894091,-1.166076304,5.374259609
+65.26659767,-2.285067611,-3.930202492,-0.08023256958,4.546917954
+65.27663767,-2.547630398,-3.712108073,-0.3882217902,4.518947128
+65.28667867,-2.641769693,-4.211942393,-1.252707481,5.127248957
+65.29671867,-2.665276669,-4.56228475,0.01948350728,5.283798016
+65.30675967,-2.275225431,-4.084422805,0.4310970837,4.69521087
+65.31679967,-2.850981315,-3.746411056,-0.5963867605,4.745457557
+65.32684067,-2.338365713,-3.600508407,-0.9722884673,4.401926835
+65.33688067,-2.401661968,-4.348652633,0.6578146845,5.011135609
+65.34692167,-2.368075854,-4.057171857,-0.9758067369,4.7979814
+65.35696167,-3.276162478,-3.947136029,-1.080532123,5.242201168
+65.36700267,-2.42739498,-3.805750062,0.01710719883,4.514008482
+65.37704267,-1.875255269,-3.562464083,0.1365254688,4.0281971
+65.38708367,-2.841426964,-4.499816899,-1.722370461,5.593623094
+65.39712367,-2.998822315,-4.951481856,0.3922493523,5.802065788
+65.40716467,-1.511835321,-4.35792661,1.534348564,4.861213417
+65.41720467,-2.50761527,-4.203085907,-0.2550847828,4.900931925
+65.42724567,-3.078191544,-4.693387219,-0.1369020295,5.614435763
+65.43728567,-1.580287944,-4.149228081,1.663108345,4.741237499
+65.44732667,-2.498760247,-3.931599977,-0.3704041547,4.673165992
+65.45736667,-2.730664035,-4.245627325,-0.5312306517,5.075833278
+65.46740767,-1.898789582,-4.691131363,0.9504181266,5.1493116
+65.47744767,-3.059335442,-3.719568243,-0.2454088104,4.822338307
+65.48748867,-2.258322739,-2.998577609,-1.431163918,4.017426967
+65.49752867,-2.502746294,-4.077806388,-1.217294989,4.937008309
+65.50756967,-2.91450605,-3.855545828,1.047723981,4.94543271
+65.51760967,-2.095314207,-3.232981375,-1.941334653,4.314080486
+65.52765067,-3.139243199,-3.125981129,-0.7973660874,4.501377407
+65.53769067,-2.423893959,-3.980924749,0.3285655725,4.672363334
+65.54773167,-3.032637056,-3.508670284,0.439156301,4.658380935
+65.55777167,-2.452400305,-3.33586752,-1.01124788,4.262030225
+65.56781267,-2.432343186,-3.944210082,1.083033562,4.758786426
+65.57785267,-2.437580245,-3.898281958,0.3716899574,4.612651417
+65.58789367,-2.441305944,-3.002823273,-0.5323188186,3.906441558
+65.59793367,-2.160577759,-3.644049114,-1.281170558,4.425899704
+65.60797467,-2.578605146,-4.250120618,0.4491065079,4.991435306
+65.61801467,-1.816242099,-3.457005164,0.5298863769,3.940862804
+65.62805567,-2.460232066,-3.245509912,-0.8514475697,4.160653719
+65.63809567,-2.55118112,-3.340590316,-0.3745533389,4.219995138
+65.64813667,-1.760671477,-3.819067096,0.3216313595,4.217663366
+65.65817667,-2.967200573,-4.051338674,-0.7657677341,5.079766187
+65.66821767,-2.029435383,-3.562069104,-1.026501512,4.22618618
+65.67825767,-2.399703443,-3.781402549,-1.104286437,4.612703154
+65.68829867,-2.405694208,-2.730363781,-1.405346122,3.900929213
+65.69833867,-2.685145508,-2.860735055,-2.299813997,4.547851787
+65.70837967,-2.159966725,-3.273028955,-0.5577477747,3.960966722
+65.71841967,-2.284029292,-4.060952082,0.08473784924,4.659968038
+65.72846067,-3.100997146,-3.362917324,-0.4404678315,4.595585724
+65.73850067,-2.702725747,-3.536180849,-0.1287597817,4.452626252
+65.74854167,-3.304945105,-4.453958356,0.3392344022,5.55657153
+65.75858167,-2.66511207,-4.43597846,2.099593053,5.584712906
+65.76862267,-2.188979439,-3.67740017,0.7217311835,4.340022915
+65.77866267,-3.578419381,-3.827224254,0.4264087862,5.256857922
+65.78870367,-2.314936212,-3.397645692,1.577401612,4.403535144
+65.79874367,-2.706635487,-4.119058203,0.9726164961,5.023793287
+65.80878467,-3.299019829,-4.009771403,0.902294957,5.270287917
+65.81882467,-2.335831968,-3.849198675,1.539126908,4.758293083
+65.82886567,-2.609010082,-3.533591117,0.9938477361,4.503435701
+65.83890567,-2.397137247,-3.636832188,0.4720012808,4.381278415
+65.84894667,-2.415303961,-3.418027624,0.08698318005,4.186188259
+65.85898667,-2.475359397,-3.247154441,0.7901751816,4.158821098
+65.86902767,-2.23901611,-2.760335146,-1.521309273,3.866138275
+65.87906767,-2.037959454,-3.081782611,0.05867797852,3.695146263
+65.88910867,-2.234540944,-3.526367759,-1.083874977,4.313145925
+65.89914867,-2.396074954,-2.623138417,-0.9858545923,3.686996015
+65.90918967,-1.580825596,-2.844882376,-2.62705459,4.182556768
+65.91922967,-3.333760183,-3.281359191,-1.227433476,4.836100499
+65.92927067,-1.158709324,-3.054911439,-1.074008385,3.439271029
+65.93931067,-2.3892112,-3.493550262,-2.237002621,4.787212583
+65.94935167,-3.145863124,-3.410166335,-2.379807415,5.214323788
+65.95939167,-1.231344971,-3.136088919,-0.5648556501,3.416185892
+65.96943267,-2.975819661,-3.719661214,-1.876952131,5.119993311
+65.97947267,-2.556878939,-3.695245288,-0.1977282751,4.497951102
+65.98951367,-1.438048869,-3.729510556,-0.09442376196,3.998268298
+65.99955367,-2.93564812,-3.618259385,-0.06353116751,4.65981406
+66.00959467,-2.083741106,-4.248218518,-0.2443908101,4.738044369
+66.01963467,-1.808095612,-4.378816957,1.910186536,5.108038791
+66.02967567,-2.797815214,-3.809996603,0.03450675845,4.727053501
+66.03971567,-1.956112029,-3.043586844,-0.07763523638,3.618815052
+66.04975667,-2.22117684,-3.887956067,0.279856512,4.486440527
+66.05979667,-2.491000114,-3.712234958,0.869752863,4.554364938
+66.06983767,-1.977968921,-3.250284163,0.1089611095,3.806386833
+66.07987767,-2.748713805,-3.242897961,-0.3918453097,4.269116713
+66.08991867,-2.629599591,-3.139179757,0.3325422639,4.108506774
+66.09995867,-1.973033725,-3.002470101,0.5352552903,3.632380351
+66.10999967,-3.071967475,-3.218484081,-0.6728923148,4.499823109
+66.12003967,-2.115014354,-2.757581985,1.061788874,3.63386017
+66.13008067,-2.311790264,-2.792357715,-0.8180178684,3.716287
+66.14012029,-3.637813936,-2.866112155,-0.2971876591,4.640755285
+66.15016129,-1.241546462,-2.81651344,0.5645112491,3.129354331
+66.16020129,-2.804735101,-3.098322045,0.6634093004,4.231577765
+66.17024229,-2.338622552,-2.945007466,-0.5451879555,3.799928199
+66.18028229,-1.994666669,-2.733616002,-0.2605729795,3.39400204
+66.19032329,-2.830438292,-2.623130816,-0.5986975801,3.90520614
+66.20036329,-1.836059336,-2.595753275,-0.7908733392,3.276359197
+66.21040429,-2.060687435,-2.660974288,-0.08844790757,3.366755099
+66.22044429,-2.622263966,-2.666896056,-1.230264698,3.937277499
+66.23048529,-1.484688015,-2.116849356,-0.3708964902,2.612070808
+66.24052529,-2.359915041,-2.660011544,-1.037794824,3.704305402
+66.25056629,-1.860190795,-2.930184482,-0.09626212656,3.472111359
+66.26060629,-1.274420386,-2.492793455,0.01919699371,2.799738391
+66.27064729,-2.029515636,-2.417535112,-1.330961353,3.425619339
+66.28068729,-1.529301539,-2.935277115,-0.063089118,3.310376893
+66.29072829,-1.625742737,-2.941898209,0.305667876,3.37509072
+66.30076829,-1.479204935,-2.663092734,-0.3861670786,3.070705971
+66.31080929,-2.242692839,-2.569802747,-0.52239317,3.4505727
+66.32084929,-1.452315052,-2.834267049,0.2494410503,3.194449804
+66.33089029,-2.63967142,-2.91796614,-0.3077816445,3.946786179
+66.34093029,-1.6227437,-2.50496502,0.2643222141,2.996333275
+66.35097129,-1.67046005,-2.970376488,0.06041167796,3.408404734
+66.36101129,-2.663749084,-2.73960472,0.1979539776,3.826248683
+66.37105229,-1.326821378,-2.406498346,-0.1769139415,2.753722536
+66.38109229,-3.020769255,-2.622214265,-0.7005338573,4.061010001
+66.39113329,-1.637648107,-2.718135206,0.6611622155,3.241494377
+66.40117329,-2.126967671,-3.502824238,0.3879569113,4.116342998
+66.41121429,-2.593735109,-3.062414002,0.5099748534,4.045480896
+66.42125429,-0.9259558614,-1.872507078,-0.6006984973,2.173595109
+66.43129529,-2.772094774,-2.699005456,-0.5585453349,3.909106391
+66.44133529,-1.691162409,-3.453400063,0.8031852365,3.928245004
+66.45137629,-1.448118359,-3.442628322,0.2869708192,3.745809498
+66.46141629,-2.739178751,-2.426408993,-0.4264713514,3.684079077
+66.47145729,-0.8098845376,-2.054302275,-0.3610860318,2.237510653
+66.48149729,-1.98538436,-3.362788978,0.06674655139,3.905708114
+66.49153829,-1.441186485,-3.174770882,0.8382661915,3.585927891
+66.50157829,-1.026412342,-2.859579353,-0.1187160194,3.040527893
+66.51161929,-2.207466727,-2.64662142,0.1435204929,3.449364061
+66.52165929,-1.029034526,-2.783334585,0.6072602427,3.028964917
+66.53170029,-1.548171528,-2.8987671,-0.2977659488,3.299750042
+66.54174029,-1.452598788,-2.699026213,0.1385345721,3.068220586
+66.55178129,-1.597440167,-2.28209781,0.02357480407,2.78573891
+66.56182129,-2.039430175,-2.133299913,0.02539855063,2.951421529
+66.57186229,-1.400926358,-2.195776974,-0.3955109292,2.634475294
+66.58190229,-1.820601199,-2.030343309,-0.09132590711,2.728593612
+66.59194329,-2.117218462,-2.001245956,-0.1742154515,2.918552795
+66.60198329,-2.136495709,-1.854281015,-0.6930903518,2.912618449
+66.61202429,-1.634316948,-1.481272218,-0.3102398139,2.22742183
+66.62206429,-2.119678385,-1.928190697,-0.8809286463,2.997831066
+66.63210529,-1.860459913,-2.089881413,0.1247871834,2.80080118
+66.64214529,-1.126081056,-1.979198006,-0.5649579763,2.346158735
+66.65218629,-2.10661132,-1.84342215,-1.074790742,2.998531577
+66.66222629,-1.048213174,-1.750525096,0.1619468236,2.046781802
+66.67226729,-1.399749314,-2.243037679,-0.1112204736,2.646296688
+66.68230729,-1.769064863,-2.293742979,-0.4818123239,2.936492884
+66.69234829,-0.68496433,-2.131794109,0.0120739156,2.239166817
+66.70238829,-1.462297126,-2.337008281,-0.5935140234,2.819960902
+66.71242929,-1.085717946,-2.338430763,0.2329717827,2.588690353
+66.72246929,-0.8703883092,-2.600222302,-0.02890512586,2.742182951
+66.73251029,-1.344250613,-2.25492653,-0.4217678511,2.65887034
+66.74255029,-0.9207424839,-2.268055283,-0.2356357741,2.459139221
+66.75259129,-1.464175398,-2.356361834,-0.3030693734,2.790717065
+66.76263129,-1.055745338,-2.334953131,-0.3170687771,2.582079966
+66.77267229,-1.158622566,-2.115523208,-0.272231158,2.427334854
+66.78271229,-1.184756477,-1.825457165,-0.5459065783,2.243647869
+66.79275329,-1.525303652,-2.102038359,-0.6892177409,2.687031371
+66.80279329,-1.293493272,-2.220230468,-0.3521789682,2.593564767
+66.81283429,-0.9729607509,-2.255177522,-0.4166117764,2.491193218
+66.82287429,-1.569216095,-2.015661535,-0.468470732,2.597074393
+66.83291529,-0.8511959202,-2.228080647,-0.4652348828,2.430086698
+66.84295529,-1.409198414,-2.4621596,-0.1207069963,2.839478869
+66.85299629,-0.9770042467,-2.407475562,0.1387900954,2.601872128
+66.86303629,-0.9784187613,-2.535980113,0.01836201131,2.718241264
+66.87307729,-1.279043487,-2.70704567,0.1413500065,2.997336872
+66.88311729,-0.7197808447,-2.398455063,0.5041551197,2.554377329
+66.89315829,-1.027535592,-2.488668245,-0.005586429834,2.692458028
+66.90319829,-0.9937044793,-2.673097613,0.2751728922,2.865068858
+66.91323929,-0.9789320006,-2.542216461,0.663748439,2.803878454
+66.92327929,-1.484168782,-2.281038587,-0.2757102513,2.735308054
+66.93332029,-0.8300849135,-1.772965248,0.4210615075,2.002433402
+66.94336029,-1.267956727,-2.611181154,-0.1462803787,2.906437549
+66.95340129,-1.371065066,-2.239079114,0.07962153554,2.626715493
+66.96344129,-0.6037969003,-1.68627209,-0.606081444,1.890877832
+66.97348229,-1.822108611,-1.78247399,-1.051244005,2.757246321
+66.98352229,-0.8119864655,-2.28468608,0.2762288994,2.440371879
+66.99356329,-1.549118923,-2.430657434,-0.09824842572,2.884010705
+67.00360329,-1.351119483,-1.456314693,-0.1700610048,1.993814708
+67.01364429,-0.8881792668,-1.891271232,-0.168981024,2.096264265
+67.02368429,-1.882520581,-2.348059665,0.5388150752,3.057382805
+67.03372529,-0.6577254414,-2.052104014,0.201796183,2.164360262
+67.04376529,-1.777190154,-2.260276586,-0.3076956904,2.89170049
+67.05380629,-0.9386739209,-1.944591406,0.6225279075,2.247239521
+67.06384629,-1.197169604,-2.345888448,-0.3625028121,2.658536432
+67.07388729,-1.691806918,-2.098986405,-0.4070428079,2.726469957
+67.08392729,-0.5547313423,-2.353294385,-0.2048934531,2.426458871
+67.09396829,-1.567666145,-2.490851887,-0.2314567691,2.952201298
+67.10400829,-0.9685631331,-1.857041631,-0.4252516222,2.137184387
+67.11404929,-0.8597924966,-2.141588633,-1.038920413,2.530810273
+67.12408929,-1.528081225,-2.532146386,-0.1705322903,2.96241098
+67.13413029,-1.048373461,-2.309646382,0.1112456167,2.538883398
+67.14417104,-1.600053872,-2.144848748,-1.021146047,2.864138229
+67.15421204,-1.391689219,-1.783599287,-0.1776658934,2.269270911
+67.16425204,-0.9347205453,-2.222146747,0.09713628531,2.412690224
+67.17429304,-1.877232213,-2.169108554,0.05550995708,2.869166091
+67.18433304,-1.450574335,-2.002375638,-0.02503193021,2.472711204
+67.19437404,-1.485366438,-1.494021779,0.4030304486,2.144958758
+67.20441404,-1.591942176,-1.880633538,0.1462599134,2.468289764
+67.21445504,-1.641127931,-2.184238955,0.6722356725,2.813556734
+67.22449504,-1.576472051,-1.818894835,0.5424175447,2.467358778
+67.23453604,-1.534019511,-1.458793766,-0.03035640478,2.117124613
+67.24457604,-1.200769881,-1.833754802,0.2523202193,2.206393092
+67.25461704,-1.801825643,-2.083627085,0.3869699013,2.7816943
+67.26465704,-0.8760747264,-1.78541397,0.1398993123,1.993685479
+67.27469804,-1.542043061,-1.606211575,-0.491445027,2.280204078
+67.28473804,-0.9817065775,-1.246901781,-0.07092438698,1.588566059
+67.29477904,-1.197297877,-1.660450055,-0.6771011406,2.156173125
+67.30481904,-1.52955297,-1.793845509,0.1052147985,2.35976358
+67.31486004,-0.6849871342,-1.570527479,0.3709549624,1.753103397
+67.32490004,-1.73615074,-1.608200359,-0.8566053987,2.516803647
+67.33494104,-1.183920106,-1.256828014,0.106832723,1.729941243
+67.34498104,-0.8528436656,-1.748836128,-0.3648107082,1.979610309
+67.35502204,-1.767777306,-1.887582808,-0.09176971078,2.587745571
+67.36506204,-0.6725188239,-1.458531227,0.4146517897,1.658773949
+67.37510304,-1.480418086,-1.358380994,-0.7347856772,2.13933322
+67.38514304,-1.470601195,-1.677848299,-0.08452384114,2.23270846
+67.39518404,-0.8475952048,-1.674671653,0.4485469294,1.929802354
+67.40522404,-1.728674051,-1.392286659,-0.1313600385,2.223517838
+67.41526504,-1.056155812,-1.466687508,0.02222702086,1.807520784
+67.42530504,-1.04782353,-1.657628919,0.5563450277,2.038427721
+67.43534604,-1.614083097,-1.318166622,-0.1863998795,2.092264897
+67.44538604,-0.7567301314,-1.328418984,-0.09583411038,1.531836044
+67.45542704,-1.563339351,-1.610540999,0.1409787083,2.248943582
+67.46546704,-1.028694803,-1.427380477,0.01286621332,1.759486733
+67.47550804,-0.922211743,-1.26411306,-0.530335443,1.652184012
+67.48554804,-1.236101243,-1.293476315,-0.1759953439,1.797776855
+67.49558904,-0.8409646815,-1.406078779,-0.3388098943,1.673042519
+67.50562904,-1.428171313,-0.9822536577,-0.3317265773,1.764805392
+67.51567004,-0.8586822566,-1.036180189,-0.7677277207,1.549325806
+67.52571004,-1.254978686,-1.22679423,0.08495887399,1.757046839
+67.53575104,-1.042983205,-1.342498202,-0.211065774,1.713086148
+67.54579104,-1.055127433,-1.074102598,-0.2719253486,1.530011009
+67.55583204,-1.193100453,-1.049599841,-0.3280065787,1.622571057
+67.56587204,-1.08468372,-0.9698269357,0.1416201478,1.461902638
+67.57591304,-0.8419397778,-1.27359739,-0.626069566,1.650113936
+67.58595304,-1.458007024,-1.122194266,0.006278740168,1.839876049
+67.59599404,-0.5452571719,-0.8208621003,-0.4181741524,1.070509034
+67.60603404,-1.267679569,-0.7997468544,-0.3542015201,1.540151044
+67.61607504,-0.8315662325,-1.237643592,-0.3295806491,1.527051887
+67.62611504,-1.148133976,-1.004321561,0.08079565644,1.5275475
+67.63615604,-1.168949041,-0.6470370966,-0.358624354,1.383369181
+67.64619604,-0.7323576209,-0.7837908261,-0.2947815299,1.112462087
+67.65623704,-1.199709854,-0.8830592255,0.05078540683,1.490528928
+67.66627704,-0.8735746032,-0.6953758822,-0.1812888283,1.131170122
+67.67631804,-0.9958373243,-0.653051031,-0.2481037921,1.216438703
+67.68635804,-1.437747591,-0.9510035791,0.2814381838,1.746634877
+67.69639904,-0.9849964403,-0.5073207291,0.1806421262,1.122596939
+67.70643904,-1.201211711,-0.3372896183,-0.3898841536,1.307166215
+67.71648004,-1.024120087,-0.7105752077,0.6420131689,1.402112687
+67.72652004,-1.085504157,-0.9980235252,0.1732933456,1.484722471
+67.73656104,-1.142529201,-0.5304295101,0.2178491288,1.278353114
+67.74660104,-0.8291342293,-0.507538611,-0.08217969239,0.9756087914
+67.75664204,-1.157643522,-0.7712930605,0.3298630697,1.429629726
+67.76668204,-0.9343327287,-0.6433656299,0.1741447002,1.147703515
+67.77672304,-1.065605205,-0.6826492712,0.2011962587,1.281407201
+67.78676304,-0.9264034657,-0.8739873435,0.1604341489,1.283673001
+67.79680404,-0.7006872006,-0.7368200697,0.2946634161,1.058627837
+67.80684404,-1.182844656,-0.7132508205,-0.1903678,1.394305603
+67.81688504,-0.5837803097,-0.5846422258,0.3719782251,0.9060760355
+67.82692504,-0.8609160391,-0.6017898801,-0.1360956985,1.059173983
+67.83696604,-1.154536239,-0.8019562248,-0.1728027642,1.416315116
+67.84700604,-0.3794350696,-0.6049508849,0.1530409294,0.73031368
+67.85704704,-1.084486449,-0.5853416259,-0.1984544992,1.248246717
+67.86708704,-0.5470346889,-0.5735565262,-0.1188411498,0.8014594553
+67.87712804,-0.8134848145,-0.6326476105,-0.1544822681,1.042048614
+67.88716804,-0.9360943486,-0.589737855,-0.144469496,1.115766464
+67.89720904,-0.4617735504,-0.7145043173,-0.2414818203,0.8843442208
+67.90724904,-0.8992626641,-0.8479722771,-0.2030217594,1.252576607
+67.91729004,-0.7288362084,-0.7427570401,-0.2480944365,1.069785534
+67.92733004,-0.4248082571,-0.7207237083,-0.06114784241,0.8388347737
+67.93737104,-1.109608134,-0.7246740872,-0.1347976166,1.332123546
+67.94741104,-0.5193249898,-0.8550463848,-0.3340467525,1.054699008
+67.95745204,-0.9989174914,-0.933813569,0.03597148597,1.367895421
+67.96749204,-0.7000110432,-0.7925009117,0.1272687417,1.065021356
+67.97753304,-0.7201774321,-0.930516251,0.08010919333,1.179378442
+67.98757304,-0.895470964,-0.5124106573,-0.03694855571,1.032374992
+67.99761404,-0.7643873526,-0.5612228481,-0.2370870531,0.9774811409
+68.00765404,-1.11685415,-1.016213555,-0.1767706847,1.520296372
+68.01769504,-0.9907203528,-1.007355974,0.2339699024,1.432143425
+68.02773504,-0.779379979,-0.6033097542,-0.2204979175,1.009967892
+68.03777604,-1.016519438,-0.4246237774,-0.3806771278,1.165560893
+68.04781604,-0.831694652,-0.818002958,0.2707640916,1.197563371
+68.05785704,-0.9455236416,-1.033165291,-0.1049569362,1.404443461
+68.06789704,-1.186955103,-0.6995719904,-0.2720206583,1.404371256
+68.07793804,-0.7936942553,-0.6298107608,-0.1180020744,1.020066985
+68.08797804,-0.8494337887,-0.8593883809,0.06371243119,1.21001877
+68.09801904,-1.10426948,-0.9014741541,-0.101393643,1.429107206
+68.10805904,-0.5144110263,-0.7218306593,-0.07325625658,0.8893956846
+68.11810004,-1.084712736,-0.7571031106,-0.3715917242,1.374004094
+68.12814004,-1.000381269,-0.8967337433,0.07313404977,1.345452592
+68.13818104,-0.7028087166,-0.7465896707,-0.05664724052,1.026910482
+68.14822117,-1.287552647,-0.6730446348,-0.4102219391,1.509656563
+68.15826217,-0.7564823556,-0.8033985867,0.3596183807,1.16062062
+68.16830217,-0.8407144207,-0.7561897025,0.1258057684,1.137739291
+68.17834217,-1.261993445,-0.657074427,-0.1990140778,1.436656138
+68.18838317,-0.5299976932,-0.757842491,0.1767051959,0.9415134212
+68.19842417,-1.180759393,-0.8393958005,0.06848025084,1.450333616
+68.20846417,-1.161987784,-0.6067602327,-0.06833173156,1.312647255
+68.21850517,-0.3745679204,-0.654965921,-0.07910405695,0.7586428254
+68.22854517,-1.305559002,-1.064608036,-0.3564749175,1.72190271
+68.23858517,-0.7814984983,-0.8565027069,0.1788125324,1.173162696
+68.24862617,-0.6209647275,-0.6843453292,-0.2217591619,0.9503172356
+68.25866717,-1.438701272,-0.9593039209,-0.5281748968,1.808063628
+68.26870717,-0.494867512,-0.9237679064,0.4320817548,1.133550017
+68.27874717,-1.148469972,-0.7927717108,-0.3531876129,1.439517889
+68.28878817,-1.397700157,-0.753836856,-0.3729547101,1.631236019
+68.29882817,-0.4077058822,-1.027542974,0.1328399688,1.113424945
+68.30886917,-1.417483919,-0.8808831111,-0.1273207819,1.673746187
+68.31891017,-1.057211819,-0.5950268443,-0.3778991157,1.270653973
+68.32895017,-0.6008746447,-0.5679838374,-0.1885399604,0.8480585444
+68.33899017,-1.615244646,-0.9045636767,0.04333196104,1.851790585
+68.34903117,-0.9774044886,-0.7994840951,0.05007204652,1.263725272
+68.35907117,-1.236644741,-0.4680925998,-0.02431623101,1.32249468
+68.36911217,-1.748674891,-0.4345334192,-0.4889552826,1.867019131
+68.37915217,-1.411139397,-0.4658823523,0.356331076,1.528179506
+68.38919317,-1.548226491,-0.6552216636,0.1314962786,1.686301269
+68.39923317,-1.901150249,-0.5140920972,0.009190653563,1.969453584
+68.40927417,-1.382476639,-0.3897630432,0.3890877628,1.488135133
+68.41931417,-1.605162146,-0.616526837,0.1907355899,1.730037838
+68.42935517,-1.517189324,-0.5327130671,0.03279761732,1.608329053
+68.43939517,-1.210206337,-0.5197193479,0.5131393665,1.413513207
+68.44943617,-1.067449856,-0.5253824859,-0.2549263233,1.21674294
+68.45947617,-1.540067287,-0.5476463442,-0.1091452968,1.638180839
+68.46951717,-0.8476247332,-0.4983060037,0.2117773801,1.005796312
+68.47955717,-1.021102851,-0.6914153438,-0.5991016227,1.37099561
+68.48959817,-1.400333743,-0.3253927637,-0.08343742847,1.440061404
+68.49963817,-0.6328375719,-0.1235432157,-0.04033526301,0.6460443112
+68.50967917,-1.518604205,-0.493496011,-0.6771198517,1.734412966
+68.51971917,-1.178728655,-0.442516367,0.415447011,1.325827363
+68.52976017,-1.203071345,-0.2944152567,-0.1339217037,1.245791326
+68.53980017,-1.611411942,0.01009713644,-0.4879495615,1.683699847
+68.54984117,-1.187461691,-0.3355697329,0.4637596303,1.31823568
+68.55988117,-1.574685581,-0.520789498,-0.1014731652,1.661671804
+68.56992217,-1.557092624,-0.2144339712,-0.3930773181,1.62019417
+68.57996217,-1.722221941,-0.1268035957,-0.3450424415,1.761017278
+68.59000317,-1.539943033,-0.4097546369,0.05895279765,1.594615578
+68.60004317,-1.489695132,-0.6133879054,-0.2503193021,1.630366849
+68.61008417,-1.691815104,-0.2319057256,0.1062263668,1.710936192
+68.62012417,-1.231631485,-0.1972296172,-0.1196650225,1.25305042
+68.63016517,-1.554611066,-0.5884622484,0.06548940003,1.66354809
+68.64020517,-1.451505505,-0.7351748094,0.4224853045,1.681024706
+68.65024617,-1.248806804,-0.3570362868,0.153029235,1.307826934
+68.66028617,-1.336103248,-0.4707211791,0.2128871816,1.432505243
+68.67032717,-1.320710892,-0.6205709175,0.8086342567,1.668314984
+68.68036717,-1.080633792,-0.5102462373,0.4403836316,1.273600549
+68.69040817,-1.551126418,-0.3974488792,0.06045260847,1.602377388
+68.70044817,-1.019987275,-0.242985377,0.7430138791,1.285101381
+68.71048917,-1.283497457,-0.278961486,0.135710367,1.320455428
+68.72052917,-1.340804264,-0.6262459327,0.22745435,1.497222603
+68.73057017,-1.271925817,-0.0684540343,-0.06954795241,1.275663811
+68.74061017,-1.465244707,-0.1166376357,-0.2964947641,1.49948509
+68.75065117,-1.051960362,-0.2175564392,-0.1999654198,1.092674506
+68.76069117,-1.383083141,-0.1285723876,0.07619740605,1.391134745
+68.77073217,-1.524890546,0.1109947346,-0.7881175464,1.720098914
+68.78077217,-1.198513879,0.01514864426,-0.3437051833,1.246915495
+68.79081317,-1.559891248,-0.06733880125,-0.04793371975,1.562079659
+68.80085317,-1.340614229,0.1519081228,-0.2389452982,1.370188835
+68.81089417,-1.149466703,0.1483860159,-0.2060202116,1.177173071
+68.82093417,-1.65395029,0.1460589611,0.215198586,1.674274533
+68.83097517,-1.069854815,0.049901454,0.325958299,1.119521457
+68.84101517,-1.279455277,0.1118355276,0.1602452838,1.294291908
+68.85105617,-0.9548151597,0.007040328586,0.6922366583,1.179369809
+68.86109617,-0.8822121833,-0.01524930545,0.04961947203,0.8837380662
+68.87113717,-1.096081332,-0.066379095,-0.05666536689,1.09955056
+68.88117717,-0.7036697191,-0.1334364944,0.4308643645,0.8358232302
+68.89121817,-1.15262515,-0.03896890576,0.223090573,1.174662809
+68.90125817,-0.6894602542,-0.03802477001,0.1961430949,0.7178254933
+68.91129917,-1.108124111,-0.07485082883,-0.07539516807,1.113205337
+68.92133917,-1.010418891,-0.2186601559,0.0251915592,1.034114701
+68.93138017,-0.6346764482,-0.1743740207,-0.1584823483,0.6770060175
+68.94142017,-1.007937552,-0.4009955444,-0.2170153159,1.106269038
+68.95146117,-0.4260222121,0.007344282159,0.1423826247,0.4492456739
+68.96150117,-0.6923027319,-0.1820225625,-0.4420050645,0.8412988546
+68.97154217,-0.7263061912,-0.5656791208,0.3348764724,0.979620234
+68.98158217,-0.1868321531,-0.2745934697,-0.125869503,0.3551773625
+68.99162317,-0.7920348155,-0.5730755562,-0.0586586827,0.9793750983
+69.00166317,-0.1154882924,-0.5899045737,-0.3034026647,0.6733335939
+69.01170417,-0.8258890247,-0.3637175347,0.2920590663,0.9485154845
+69.02174417,-0.7415984874,0.03220992646,-0.5415591735,0.9188537067
+69.03178517,-0.6891639465,-0.1702318165,0.0723131007,0.71355098
+69.04182517,-0.8604219494,-0.3304232329,0.4803639686,1.039353158
+69.05186617,-0.668621143,-0.1479504714,-0.1685372204,0.7052293028
+69.06190617,-0.5938308329,0.009907148756,-0.08141896963,0.599468313
+69.07194717,-0.5399842259,-0.2605231868,0.05090527475,0.6017031179
+69.08198717,-0.8725386228,0.004670471497,0.09656033456,0.877877759
+69.09202817,-0.5234736258,0.04073283713,-0.7141543615,0.8863973449
+69.10206817,-0.8971411481,-0.05271065283,0.2848699147,0.9427574029
+69.11210917,-0.5650126844,-0.4361464102,-0.2584983873,0.7591340072
+69.12214917,-0.2421414776,-0.07210937091,0.2461040443,0.3527030723
+69.13219017,-0.6577901262,-0.03652061946,-0.9217661852,1.132993604
+69.14223017,-0.5552442893,-0.1250640491,-0.2725638646,0.6310533238
+69.15227067,-0.1586052129,-0.2925777874,-0.4303322679,0.5440066507
+69.16231067,-0.7218266393,-0.2935030545,-0.4548788792,0.9022707659
+69.17235167,-0.2735139458,-0.1935345789,-0.4479920286,0.5594303973
+69.18239167,-0.4672697139,-0.08656793637,-0.6207322276,0.7817566702
+69.19243267,-0.3593536114,-0.1095325013,-0.4191009361,0.562830331
+69.20247267,-0.5563659315,-0.4590923462,-0.6499203587,0.9709301235
+69.21251367,-0.6666644454,-0.255343376,-0.2758459067,0.7653317494
+69.22255367,-0.4399977154,-0.1386548877,-0.2706044626,0.5348363699
+69.23259467,-0.565472641,-0.1270172658,-0.3012912351,0.6531991288
+69.24263467,-0.4183202962,-0.1565322288,0.07981449366,0.4537230017
+69.25267567,-0.9955533689,-0.2868489779,-0.1914202988,1.053589378
+69.26271567,-0.6407602568,-0.2642288049,0.285192681,0.7494834443
+69.27275667,-0.6579992373,0.1825602688,0.1766730362,0.7053400667
+69.28279667,-0.8440454333,0.06976182346,0.2627463895,0.8867440841
+69.29283767,-0.4801478044,-0.3303915483,0.7402563322,0.9421676743
+69.30287767,-1.13044498,-0.03963361084,0.5592891008,1.261856162
+69.31291867,-0.9455473229,0.1621556423,0.5112501311,1.087074463
+69.32295867,-0.5812439703,0.1008297339,0.421745047,0.725175891
+69.33299967,-0.8027380706,-0.1691114718,0.8512101728,1.182178438
+69.34303967,-0.6647271167,-0.3427210969,0.7245846248,1.041317804
+69.35308067,-0.5796219161,0.2020838112,-0.1356630045,0.6286524343
+69.36312067,-0.3685634877,0.09277122919,-0.1241252786,0.3998157453
+69.37316167,-0.6268081424,-0.4426629859,0.5256804746,0.9301499492
+69.38320167,-0.3096156237,-0.03722111362,-0.3776775062,0.4897831606
+69.39324267,-0.5624529926,-0.05327417367,-0.5400798279,0.7815866727
+69.40328267,-0.3205614652,-0.2264760012,0.07305394292,0.3992341552
+69.41332367,-0.2278458211,-0.3486499908,-0.3852835643,0.5673746198
+69.42336367,-0.5816851427,-0.08065948941,-0.5653550023,0.8151624605
+69.43340467,-0.2695582861,-0.1487766647,-0.3704521018,0.4816958847
+69.44344467,-0.5495122273,-0.0614744094,0.05556784451,0.5557252705
+69.45348567,-0.5528912967,-0.1203099704,-0.3878078073,0.6859724268
+69.46352567,-0.693153721,-0.09630734199,-0.1253999716,0.7109587456
+69.47356667,-0.5122380548,0.03751299703,0.00842759192,0.51367896
+69.48360667,-0.6597781064,0.04148141321,0.2602051896,0.7104467595
+69.49364667,-0.7131231319,-0.0747112357,0.09524821937,0.7233246804
+69.50368767,-0.8393288498,0.1380209308,0.01456892252,0.8507261304
+69.51372867,-0.7290596451,0.2650132819,0.4676760954,0.9058040273
+69.52376867,-0.7498896199,0.2906158638,0.1117186564,0.8119563293
+69.53380867,-0.7976842491,0.2720031532,0.3533156669,0.9138478194
+69.54384967,-0.7278010319,0.235645349,0.02669487834,0.7654643617
+69.55388967,-0.6980067638,0.6552898568,0.03702456951,0.958117455
+69.56393067,-0.7005842896,0.4012164961,0.2217386967,0.8372341806
+69.57397067,-0.6924703277,0.1775468478,0.06396678507,0.7177254262
+69.58401167,-0.7171833654,0.5929874451,-0.1774793673,0.9473568575
+69.59405167,-0.7973455491,0.6094739985,-0.2601057869,1.036761062
+69.60409267,-0.6735588243,0.1725417956,0.05065969169,0.6971503176
+69.61413267,-0.3726959708,0.4295519204,0.3669583905,0.6768128244
+69.62417367,-0.9174320827,0.4479118852,-0.2557531196,1.052481041
+69.63421367,-0.503950394,0.4164764499,0.03403371871,0.6546578701
+69.64425467,-0.8435887657,0.1406107083,-0.2725229341,0.897597976
+69.65429467,-0.6689330189,0.5042612466,-0.07747092962,0.8412802943
+69.66433567,-0.5856027041,0.4151582316,0.02251411915,0.7181878375
+69.67437567,-0.5142956534,0.3588405548,-0.1336234957,0.6411878052
+69.68441667,-0.6571839161,0.4805154846,-0.1315319467,0.8246735618
+69.69445667,-0.63661385,0.373147449,-0.3930317098,0.8360563005
+69.70449767,-0.5263195022,0.5003233296,0.2386465055,0.7643872102
+69.71453767,-0.4865096481,0.5571741629,-0.3397588974,0.8139845169
+69.72457867,-0.7174753607,0.5274290114,-0.1755591416,0.907619561
+69.73461867,-0.6196237417,0.3312307334,-0.2007045078,0.7307049195
+69.74465967,-0.7297124136,0.3764989268,0.01515247464,0.8212558955
+69.75469967,-0.5027099072,0.5653684509,0.2151336819,0.7865374989
+69.76474067,-0.5829199285,0.3661467969,-0.3941035044,0.7932065885
+69.77478067,-0.7164657658,0.28377157,0.0916346401,0.7760453626
+69.78482167,-0.6016857266,0.2700561582,-0.05011473119,0.6614132811
+69.79486167,-0.6889401443,0.3060611013,-0.3394565964,0.8267664126
+69.80490267,-0.6328779908,0.2982642595,0.3293514383,0.7732842231
+69.81494267,-0.5941885728,0.3293070725,-0.2026422751,0.7089196709
+69.82498367,-0.8406893507,0.3285775227,-0.004601758718,0.9026311257
+69.83502367,-0.4758701641,0.06889512906,0.0627663517,0.4849108854
+69.84506467,-0.8738923263,0.1137859212,0.3173938823,0.9366823956
+69.85510467,-0.5406788386,0.4128092224,0.01472738206,0.6804130778
+69.86514567,-0.6247671718,0.4579085774,-0.1223822236,0.7842140606
+69.87518567,-0.6483750857,0.219763288,0.2654665142,0.7342742163
+69.88522667,-0.3492991779,0.2182578492,0.1071016949,0.4255786385
+69.89526667,-0.697254885,0.3899216489,-0.3097761297,0.8568340081
+69.90530767,-0.5044180982,0.5687452545,-0.09287424982,0.7658553444
+69.91534767,-0.5187866074,0.226041078,-0.1680138946,0.5903073621
+69.92538867,-0.7166418401,0.2135861797,0.1488806355,0.7624696891
+69.93542867,-0.4119146715,0.3010569262,0.04425231278,0.5121203341
+69.94546967,-0.6223180655,0.694006976,-0.09061371624,0.9365555525
+69.95550967,-0.4916535899,0.3905226696,-0.5037551701,0.8049847696
+69.96555067,-0.5022812698,0.1846695056,0.1182014644,0.5480519012
+69.97559067,-0.6071107002,0.4496961265,0.07913446248,0.7596527309
+69.98563167,-0.5370676348,0.520186175,-0.3813027799,0.8393015614
+69.99567167,-0.6156398875,0.3273386805,0.1912542379,0.7230084828
+70.00571267,-0.440351545,0.32777671,-0.1581221598,0.571270227
+70.01575267,-0.1634269731,0.5232466808,0.2650537008,0.6088915575
+70.02579367,-0.09002506608,0.2747425554,-0.1236785513,0.31445885
+70.03583367,-0.1492746008,0.268574821,0.9184566611,0.9684926325
+70.04587467,0.4072223175,0.2725533031,0.07136760592,0.4951854744
+70.05591467,-0.2420522893,0.3122243589,0.1104398704,0.4102076621
+70.06595567,0.5457465473,0.2431886226,0.4063779795,0.7225808344
+70.07599567,-0.1553370762,0.210847417,-0.2215685427,0.3430435244
+70.08603667,-0.288346596,0.2435436217,-0.6085156399,0.7160646193
+70.09607667,-0.2228137987,-0.03935373021,-0.6237797964,0.6635479932
+70.10611767,-0.5259817524,0.04787942744,-0.6338048476,0.8250198957
+70.11615767,-0.3853936382,0.3349287318,-0.4462437111,0.6781142687
+70.12619867,-0.4680594534,0.290277913,-0.8129804921,0.9819766796
+70.13623867,-0.588984624,0.07101170235,-0.3387695485,0.6831620278
+70.14627929,-0.2285192741,0.1223513978,-0.4999848855,0.5631836369
+70.15631929,-0.7407739569,0.2389139425,-0.4532837588,0.9007175435
+70.16636029,-0.5833259811,-0.1268655762,-0.1853491348,0.6250746966
+70.17640029,-0.2078384398,0.09267968372,0.3814998311,0.4442166836
+70.18644129,-0.8526203019,0.3468543474,-0.3108227813,0.9715349294
+70.19648129,-0.4595684192,0.3856557762,-0.07013559759,0.6040302241
+70.20652229,-0.4740242712,-0.01304031417,0.823491447,0.9502669218
+70.21656229,-0.3534144483,-0.1041000085,0.2284758586,0.433520244
+70.22660329,0.04034105084,0.1527726701,1.036349393,1.048325785
+70.23664329,-0.03669004025,0.2800091974,0.6044945097,0.667206806
+70.24668429,0.2891683856,0.09311804216,0.910151276,0.9595127254
+70.25672429,0.3392201496,-0.01421422494,0.3091534013,0.4591820767
+70.26676529,-0.01438696905,-0.2591735946,0.2884986967,0.3880843143
+70.27680529,0.2707707794,0.1692799995,0.0781889677,0.3287644261
+70.28684629,0.2619512778,0.1769334931,-0.9456736958,0.9971071517
+70.29688629,0.1305647989,-0.1204482844,0.3304162163,0.3751397498
+70.30692729,-0.09416400854,-0.06013209882,-0.7115780783,0.720295836
+70.31696729,-0.45153482,0.1433714894,-0.8316348642,0.9571079485
+70.32700829,-0.1707945014,0.04078938154,-1.124718947,1.138344081
+70.33704829,-0.379058582,0.1037510759,-0.1038430417,0.4064887104
+70.34708829,-0.511709101,0.2960634771,-1.161851106,1.303609519
+70.35712929,-0.5034500916,0.2325766205,0.1721636635,0.5806842569
+70.36716929,-0.4178533961,0.2213803903,-0.5280795872,0.7088573822
+70.37721029,-0.7862533079,0.1133658536,0.06499414086,0.7970384679
+70.38725029,-0.07561594157,0.2507311653,0.6456378579,0.6967295971
+70.39729129,-0.285759331,0.4957335577,0.09957223535,0.5807966817
+70.40733129,-0.32836092,-0.02000776498,0.7182368875,0.789990779
+70.41737229,-0.1582395792,-0.02302245004,1.005949718,1.018579714
+70.42741229,-0.1088706787,0.6441343195,0.7359165287,0.984040133
+70.43745329,0.004641816714,0.3624550477,0.2203955913,0.4242280339
+70.44749329,0.1602082819,-0.2353210112,1.388418433,1.41730322
+70.45753429,0.05201491183,0.1913424212,0.1455576628,0.245976638
+70.46757429,-0.2176642472,0.5252709503,-0.2895786774,0.6380776646
+70.47761529,0.03777206294,0.2569918705,0.2026060224,0.3294248784
+70.48765529,-0.2387171471,-0.1541640151,-0.1808871245,0.336856901
+70.49769629,-0.1583335184,0.5323281741,-0.3277212346,0.6448596712
+70.50773629,-0.263584862,0.4471708602,-0.6285943937,0.8152114263
+70.51777729,-0.2748865979,-0.04869619668,-0.4250118864,0.5084968681
+70.52781729,-0.3958403467,0.2681555208,-0.08744978786,0.4860498214
+70.53785829,-0.5120462295,0.4099351332,-0.6161462563,0.8999301994
+70.54789829,-0.2221565533,0.3319970841,-0.170965569,0.4345167705
+70.55793929,-0.3234682623,-0.1218632101,0.3424702513,0.4865883596
+70.56797929,-0.2088528952,0.4012962375,0.07378192127,0.4583688187
+70.57802029,0.02878769732,0.3277743711,-0.2320292115,0.40261933
+70.58806029,-0.3290784464,-0.03968496584,0.5288461572,0.6241360255
+70.59810129,0.1949066098,0.09242032316,0.7948435986,0.8235936188
+70.60814129,-0.1685741675,0.3796832839,-0.3519175977,0.5444470971
+70.61818229,0.07335817629,0.2621468306,0.2369642615,0.3609078055
+70.62822229,0.285575436,0.03164012215,0.4900943202,0.5681081496
+70.63826329,0.02082126799,0.3357355014,-0.3623753428,0.4944367919
+70.64830329,0.126372391,0.3593770368,-0.372104525,0.5325256926
+70.65834429,-0.03283019727,0.3228074173,-0.154150731,0.3592281981
+70.66838429,-0.1938577837,0.2147265512,-0.4723801804,0.5539236111
+70.67842529,-0.09020203572,0.473657797,-0.3201409042,0.5787731113
+70.68846529,-0.2015563741,0.3950566006,-0.675649277,0.8082058123
+70.69850629,-0.2642692603,0.2397432604,0.00393751502,0.3568341027
+70.70854629,-0.245364737,0.3210765318,-0.4078462154,0.5741363329
+70.71858729,-0.4433691834,0.5393592682,-0.1903514278,0.7236838529
+70.72862729,-0.1892951648,0.09771006161,-0.1300210261,0.2495703965
+70.73866829,-0.07946621887,0.3181133456,0.3259372491,0.462326801
+70.74870829,-0.4264600224,0.4142823553,0.04990715504,0.5966479236
+70.75874929,0.2360040756,0.2428604111,0.07880526423,0.3476914906
+70.76878929,-0.233515793,0.05829411338,0.6775589776,0.719036854
+70.77883029,-0.005875656875,0.1957041883,0.1160836029,0.2276182232
+70.78887029,0.3391939102,0.4513466858,0.1635396051,0.5878022984
+70.79891129,-0.1720936431,0.1343385097,0.1595056111,0.2703795427
+70.80895129,0.4322321379,0.119377376,0.3238725972,0.553144681
+70.81899229,0.1359414325,0.4317556264,-0.430705905,0.6248204306
+70.82903229,-0.02643824039,0.1812613829,-0.06889715731,0.1957076589
+70.83907329,0.3770431929,0.09583540773,-0.002427179217,0.3890396971
+70.84911329,-0.4352242312,0.4497798879,-0.7354429042,0.9657113152
+70.85915429,0.3158476592,0.2863806159,-0.3146614784,0.5298919201
+70.86919429,-0.1999313049,-0.09181520943,-0.1404167908,0.260997001
+70.87923529,-0.04586979881,0.1607163867,-0.3954764307,0.4293429895
+70.88927529,0.04681277197,0.3613258773,-0.3653872436,0.5159996735
+70.89931629,-0.2933592495,0.02400966789,-0.2791583544,0.4056667355
+70.90935629,-0.03900575235,-0.0588120305,0.3249911696,0.3325651274
+70.91939729,-0.08278242155,0.3380566268,0.0639322865,0.3538679831
+70.92943729,-0.1864413947,0.1154298568,-0.2996581078,0.3713211912
+70.93947729,0.1110871206,-0.1608835805,0.6480299538,0.6768801193
+70.94951829,-0.0323240568,0.2390315629,0.2771089053,0.3673830128
+70.95955829,0.03581934873,0.3051592413,0.08955361605,0.3200391202
+70.96959929,0.1465360391,-0.03290415084,0.4425260514,0.4673165951
+70.97963929,-0.07347907204,0.08338785505,0.3322095573,0.3503082904
+70.98968029,0.2688018391,0.2028815359,-0.01655522168,0.3371786198
+70.99972029,-0.1072632151,0.1715931763,0.008007761836,0.2025184923
+71.00976129,0.09360246571,0.08518654995,0.5054344904,0.5210395321
+71.01980129,0.1556771466,0.2935803108,-0.4004722917,0.5203871917
+71.02984229,-0.1109800891,0.2980139621,-0.1991321915,0.3752099832
+71.03988229,-0.05367596875,-0.07355396665,-0.1167846841,0.1480876702
+71.04992329,-0.06832570162,0.2483079513,-0.00868896246,0.257683407
+71.05996329,0.05523533894,0.2893525364,-0.4839389563,0.566544567
+71.07000429,-0.1137256766,0.06695446559,0.3038862294,0.3313054035
+71.08004429,0.111392126,0.1032943353,-0.2360211056,0.2806846767
+71.09008529,-0.1135419279,0.2376729441,-0.1779301876,0.3178668737
+71.10012529,0.3139110248,-0.3148403667,0.2043900079,0.4893259275
+71.11016629,-0.1226616474,-0.1672086233,0.1824079853,0.2761834111
+71.12020629,0.09321664997,0.2352347648,-0.1879067069,0.3151724431
+71.13024729,0.2128902697,-0.06770088094,-0.2003139138,0.3000522293
+71.14028729,0.170461941,-0.615059332,0.4116352111,0.7594727133
+71.15032833,0.2708692684,-0.3282100252,0.1935656422,0.4675036247
+71.16036833,0.08622858773,-0.08955727969,-0.4189459848,0.4370029907
+71.17040933,0.2962679469,-0.4023158823,0.04990306199,0.5021185927
+71.18044933,0.09462145267,-0.4356139847,0.1478228742,0.4696428059
+71.19049033,-0.1434510115,-0.2940176095,-0.4685701346,0.5714739876
+71.20053033,0.1702688733,-0.4066319679,-0.1721624941,0.4732662791
+71.21057133,-0.0178322353,-0.5047359674,-0.2433780724,0.5606329205
+71.22061133,-0.05628438424,-0.3789386775,-0.2313737386,0.4475447019
+71.23065233,-0.04425584852,-0.2548502364,-0.4209983575,0.4941121737
+71.24069233,-0.1290339705,-0.4206467571,-0.1506277835,0.4650614895
+71.25073333,-0.1788912323,-0.3739160289,-0.06227226198,0.4191576127
+71.26077333,-0.1230093466,-0.225364482,-0.1435210776,0.2941406957
+71.27081433,-0.274672535,-0.1304727692,-0.3337403584,0.451498363
+71.28085433,-0.2507422933,-0.4848695406,0.214736656,0.5865850326
+71.29089533,-0.1739967656,-0.4148510335,0.008950917721,0.4499515234
+71.30093533,-0.1491470584,-0.2642269411,-0.01661661744,0.3038697639
+71.31097633,-0.2109546403,-0.2268509539,-0.0626932615,0.3160595839
+71.32101633,-0.286998959,-0.2659735226,0.1103702885,0.4065610874
+71.33105733,-0.2746329749,-0.3826910185,-0.0786579144,0.4775591629
+71.34109733,-0.3224739067,-0.4146642515,-0.2184320962,0.5689010834
+71.35113833,-0.5176153005,-0.2382184345,0.2125474584,0.6081529774
+71.36117833,-0.3926612521,-0.1595407857,-0.1718204319,0.4573383672
+71.37121933,-0.5072218746,-0.2562472459,-0.1905093026,0.5993583865
+71.38125933,-0.636010125,-0.3653978052,0.2257990032,0.7674696248
+71.39130033,-0.5757638136,0.01280249694,0.08452501059,0.5820758974
+71.40134033,-0.6039523632,0.1592786477,-0.01097639322,0.6246988281
+71.41138133,-0.7701474448,-0.3707162132,0.3208823311,0.9129748451
+71.42142133,-0.264274943,-0.2353117288,0.08978750467,0.365068009
+71.43146233,-0.9228419998,0.08462167237,-0.2371385086,0.9565734975
+71.44150233,-0.5378354473,-0.2264210008,0.18047665,0.6108234271
+71.45154333,-0.2182539023,-0.2927507554,0.1738973629,0.4044478502
+71.46158333,-0.9262280492,0.1085891718,0.09889395833,0.9378006304
+71.47162433,-0.479858623,-0.1460963376,-0.312623139,0.5910513218
+71.48166433,-0.6257280155,-0.4397237733,0.4112627435,0.8683487723
+71.49170433,-0.4445133738,-0.1025581891,0.1469048613,0.4792612648
+71.50174533,-0.5959479635,0.2069262194,-0.4669849545,0.7848868601
+71.51178533,-0.4691025602,-0.2236611698,0.07412105978,0.5249528192
+71.52182633,-0.5485417722,-0.2205005122,0.3962459242,0.7117087777
+71.53186633,-0.7170973382,-0.001254520118,-0.1396484667,0.7305695453
+71.54190733,-0.6725663325,0.2483092669,-0.004942066669,0.7169570334
+71.55194733,-0.3118612834,-0.01101140343,0.3307962853,0.4547580603
+71.56198833,-0.9064597826,-0.04425900053,0.3686546677,0.9795582987
+71.57202833,-0.3910726367,-0.04360051269,-0.1169390506,0.4105040237
+71.58206933,-0.8018328486,0.1035852525,0.3744708931,0.8910074474
+71.59210933,-0.7158237416,0.09194213055,0.4055938679,0.8278667586
+71.60215033,-0.3144742944,0.1728278889,-0.1192194647,0.3781227867
+71.61219033,-1.028651752,0.1007847286,0.04018440485,1.034358147
+71.62223133,-0.2634892234,-0.07965526666,0.3870079082,0.4749175227
+71.63227133,-0.5564944606,0.1897324635,0.118456403,0.5997636299
+71.64231233,-0.6433383673,0.07764109273,-0.3590593868,0.7408346896
+71.65235233,-0.404553904,0.07961075474,0.315733273,0.5193161207
+71.66239333,-0.5748080496,0.1339041438,-0.1328908396,0.6049748663
+71.67243333,-0.5868714037,-0.004078743551,-0.2891775584,0.6542616762
+71.68247433,-0.3952827416,-0.05930867381,0.4716802686,0.6182622748
+71.69251433,-0.50564806,0.1094341675,-0.6363179809,0.8200953423
+71.70255533,-0.6326948268,0.2117153814,-0.105692516,0.6754976347
+71.71259533,-0.1837122799,-0.1864569629,-0.2119861257,0.336830103
+71.72263633,-0.7083213253,-0.277755717,0.01836961269,0.7610550446
+71.73267633,-0.2192670421,0.3902293951,-0.4476189762,0.6330243001
+71.74271733,-0.7564714652,0.2131209241,-0.6396976715,1.013352218
+71.75275733,-0.3416217107,-0.1997308733,0.1912168157,0.4395016332
+71.76279833,-0.5541015241,-0.1296323416,0.2000466961,0.6032012298
+71.77283833,-0.6440691961,0.3271605597,-0.4789553744,0.8667510668
+71.78287933,-0.363776957,0.1618834909,0.2732146597,0.482893559
+71.79291933,-0.5580856341,-0.01353331667,-0.005361896753,0.5582754478
+71.80296033,-0.4745485472,0.1556475268,0.1754521376,0.5293448109
+71.81300033,-0.675165493,0.1490429871,0.002251178026,0.6914241265
+71.82304133,-0.5872686855,0.2331743887,0.3694235766,0.7319348218
+71.83308133,-0.5255449654,0.3466712565,-0.1080892897,0.6387971237
+71.84312233,-0.5160115554,0.333090148,-0.06693015397,0.6178160062
+71.85316233,-0.6397209142,0.01155372354,0.3753865671,0.7418162922
+71.86320333,-0.4450125433,0.3045908554,0.04232740939,0.5409282415
+71.87324333,-0.5717838697,0.5434097441,-0.2684333915,0.8332391189
+71.88328433,-0.408888847,0.1528372362,-0.04046741009,0.4383912878
+71.89332433,-0.6540916892,0.04179248052,0.4394357979,0.7891047901
+71.90336533,-0.4769206895,0.3178595765,-0.08687091351,0.5796849231
+71.91340533,-0.5972255436,0.27908351,-0.6706569242,0.9403970786
+71.92344633,-0.4826139772,0.1292866524,0.4106938094,0.6467616984
+71.93348633,-0.5306566379,0.1208630987,-0.1395484793,0.561852413
+71.94352733,-0.3951373652,0.3835379877,-0.2090069693,0.5889981653
+71.95356733,-0.4768140144,-0.1331794179,-0.2756155264,0.5666147545
+71.96360833,-0.6219208934,0.07136121053,0.0981747508,0.6336531399
+71.97364833,-0.5821510562,0.3318046742,-0.2181110841,0.7046748463
+71.98368933,-0.6057609801,-0.1283737284,-0.5112033534,0.8029664051
+71.99372933,-0.5458236575,-0.2308240273,0.4246592993,0.7290670182
+72.00376933,-0.5797244617,0.03102328886,-0.2122550976,0.618138433
+72.01381033,-0.7189405999,0.1199442727,-0.4023673743,0.8325633421
+72.02385033,-0.3914533636,-0.1747796712,0.3981632262,0.5850791605
+72.03389133,-0.6998076332,-0.2465699943,0.2254312134,0.7754654844
+72.04393133,-0.4769093605,0.3308641495,0.01421224236,0.5806165787
+72.05397233,-0.5664931628,-0.2203896892,-0.1470200515,0.6253806954
+72.06401233,-0.4262459412,-0.4037925235,0.4566739744,0.743831381
+72.07405333,-0.5210526227,0.1745030431,0.02183291852,0.5499307448
+72.08409333,-0.5809339948,0.2077609094,-0.5574752945,0.8315212599
+72.09413433,-0.3197260808,-0.05325088531,0.4156475705,0.5270894861
+72.10417433,-0.5298510377,-0.05437032561,0.09846418798,0.5416580571
+72.11421533,-0.6337458638,0.3327836442,-0.4826285952,0.8633128834
+72.12425533,-0.5473940369,0.08458115299,0.0709115231,0.5584108229
+72.13429633,-0.3700599364,-0.04470022777,0.1523492038,0.4026819425
+72.14433633,-0.7371334074,0.3157936455,0.2373729819,0.8363236331
+72.15437742,-0.5190171704,0.07767507054,-0.2953685904,0.6022083061
+72.16441742,0.007311699349,0.06039071934,0.1364693356,0.1494134515
+72.17445842,-0.4425356262,0.2231722878,-1.389331768,1.475088612
+72.18449842,-1.008022045,0.3970240425,-0.8024093109,1.348182938
+72.19453942,-0.8883306366,-0.01181240802,5.066766729,5.144064146
+72.20457942,0.0874638029,-0.6257660955,-1.981850011,2.080135233
+72.21462042,-1.149243339,1.162915299,-1.125944524,1.985165816
+72.22466042,-0.202487397,0.4099160932,-0.542601732,0.7095413934
+72.23470142,-0.7332853547,-0.5596214053,1.04980442,1.39748805
+72.24474142,0.09769483144,0.1340450982,-0.6343077081,0.6556360553
+72.25478242,-0.6165582658,0.2463996576,0.09093472838,0.6701686438
+72.26482242,-0.2803929574,-0.09110311906,-0.7670775104,0.821783363
+72.27486342,-0.6549390969,-0.04057360101,0.3148737323,0.7278302722
+72.28490342,-0.3487079148,0.009674117798,-0.1150328583,0.3673191485
+72.29494442,-0.4551669277,-0.3314688613,0.008020040989,0.5631277467
+72.30498442,-0.2849207123,0.006040164633,0.419214372,0.5069092479
+72.31502542,-0.5917348984,-0.143133188,-0.1021526116,0.6173106637
+72.32506542,-0.8030297736,0.009930061391,-0.1439105022,0.8158833593
+72.33510642,-0.372787297,-0.1189951326,0.562472325,0.6852045875
+72.34514642,-0.3820454494,-0.2867454822,0.36639238,0.6020175023
+72.35518742,-0.6763046037,0.0825354041,-0.2601929104,0.729314994
+72.36522742,-0.4468029607,0.445696229,-0.2408871585,0.6755032475
+72.37526842,-0.4031302898,-0.08281016842,-0.3341426468,0.5301158957
+72.38530842,-0.3605305829,-0.1361611142,0.1914138669,0.4303038678
+72.39534942,-0.4176126735,0.2444696562,-0.08867068648,0.4919636658
+72.40538942,-0.911737918,0.5463049199,0.2736204565,1.097535079
+72.41543042,-0.3716334587,0.303996358,0.3597534513,0.5999564643
+72.42547042,-0.1874683668,-0.06832059444,-0.4062072408,0.4525664754
+72.43551142,-0.5794663802,-0.0661419767,-0.1942181915,0.614716807
+72.44555142,-0.4948382759,0.3874805094,0.08153942227,0.6337623702
+72.45559242,-0.4948797546,0.3515579573,-0.2749980605,0.6664254663
+72.46563242,-0.5301480398,0.06343376569,0.2490773535,0.5891691732
+72.47567342,-0.3795775224,-0.09126367995,0.2671926123,0.4730750964
+72.48571342,-0.7939650545,0.2146074508,0.4331915563,0.929565377
+72.49575442,-0.6466418248,0.3403721973,0.3383070338,0.8052642618
+72.50579442,-1.131185456,-0.3417612764,0.2678539324,1.211662922
+72.51583542,-0.9511488093,-0.5788742034,-0.5929959601,1.261516393
+72.52587542,-0.350506226,-0.3572512085,0.427748968,0.6583708834
+72.53591642,-1.032479705,0.3265141134,-0.6003324616,1.238153816
+72.54595642,-0.7481005912,0.6570424866,-0.1593816501,1.008346088
+72.55599642,-0.9948418359,0.6354014298,0.5652415663,1.308794592
+72.56603742,-1.16169038,0.8721269057,-0.4571622169,1.522868074
+72.57607742,-1.589183752,0.9019884168,-0.3128868484,1.853911077
+72.58611842,-1.093699688,0.752350713,-0.4871280277,1.414038301
+72.59615842,-1.033224202,-0.002717365567,0.5910827512,1.19035224
+72.60619942,-0.248681899,-0.3378842801,-0.8544559622,0.9518946711
+72.61623942,2.564491137,1.319272331,-0.6627017874,2.959099176
+72.62628042,1.735615427,0.6498091154,0.5966305894,1.946941411
+72.63632042,0.3377204119,-1.224153042,-0.5841035146,1.397777759
+72.64636142,-2.133753803,-0.2511994908,-0.2491071743,2.162882535
+72.65640142,-2.281525368,-0.7202489875,-0.5929222852,2.46488812
+72.66644242,0.5750390147,-1.019886045,0.06362472296,1.172555124
+72.67648242,-0.7736348704,-1.254164754,0.02951849878,1.473876346
+72.68652342,0.2046108682,-0.5327117515,0.770663023,0.9589415584
+72.69656342,0.3734857104,-0.1017570292,-0.3564755023,0.5262326981
+72.70660442,0.143822191,0.9624977432,-1.924373635,2.156455568
+72.71664442,-1.125448095,0.4668125712,0.1289568329,1.22522539
+72.72668542,-1.552444527,-1.841087357,4.405998616,5.021206077
+72.73672542,-2.150283297,-4.979337991,0.08475071311,5.424454606
+72.74676642,-2.745086193,-5.413021883,-2.390775622,6.523198003
+72.75680642,-2.903721153,-3.665261935,-0.04213912904,4.67627173
+72.76684742,-1.436498626,-1.982801937,0.7808822018,2.569982264
+72.77688742,0.2214574456,0.6355688064,6.167461807,6.204077389
+72.78692842,0.2059864439,1.993126658,2.318488249,3.064371396
+72.79696842,-0.9493384382,0.1081156021,2.123412271,2.3284785
+72.80700942,-2.088874961,-2.597370615,2.544377884,4.193279329
+72.81704942,-0.9624136895,-1.699217387,2.033163421,2.819101512
+72.82709042,0.1364436078,-1.187142214,1.284773612,1.754584489
+72.83713042,1.429495415,-2.107830026,1.535601622,2.973966527
+72.84717142,2.515916854,-3.003392499,-0.6297574049,3.968223596
+72.85721142,3.927894596,-3.24493513,0.781992588,5.154558407
+72.86725242,6.597811616,-3.026509759,4.837321402,8.722990186
+72.87729242,6.222209287,-5.525062137,5.556337139,10.00575247
+72.88733342,-0.1402033675,-6.190316234,5.45095628,8.249399761
+72.89737342,-4.666730932,-6.629320507,3.041415773,8.658895881
+72.90741442,-6.034320706,-4.444775596,3.888603646,8.443358029
+72.91745442,-7.117952439,-3.296587679,4.445609409,9.016439445
+72.92749542,-7.287619926,-3.14008783,4.167737442,8.963235529
+72.93753542,-5.308389468,-1.991613399,4.586354814,7.292473733
+72.94757642,-2.993365401,-1.307013497,5.069032525,6.030224826
+72.95761642,-1.671036877,-1.846430543,4.9505808,5.541653206
+72.96765742,-0.9602987516,-2.679328113,3.754474366,4.711374597
+72.97769742,-1.038779788,-3.296904014,2.050090526,4.018894212
+72.98773842,-1.124429803,-3.154338956,0.2649794412,3.359227699
+72.99777842,-1.18302592,-2.658304742,-0.9513571894,3.061244017
+73.00781942,-1.455778942,-2.39811607,-1.38127489,3.127007089
+73.01785942,-2.069337806,-2.536069283,-1.278386698,3.51398334
+73.02790042,-2.730366997,-2.751366979,-1.079597154,4.023736349
+73.03794042,-3.111661298,-2.896400147,-0.9672844201,4.359725794
+73.04798142,-2.966918737,-2.859502755,-1.002409229,4.240776705
+73.05802142,-1.941460076,-2.383906606,-0.801462062,3.177203073
+73.06806242,-0.5312540406,-2.057470297,-0.1711801618,2.13183431
+73.07810242,0.585517956,-2.095113209,0.5745772308,2.249993251
+73.08814242,0.9889711583,-2.14952696,1.272276358,2.686487899
+73.09818342,1.177583916,-2.250723259,1.621970844,3.013842811
+73.10822342,1.451285649,-2.064275725,2.239761922,3.374018046
+73.11826442,1.52034419,-1.821535876,2.614096575,3.530288984
+73.12830442,0.680807983,-1.661981733,2.531254978,3.103696917
+73.13834542,-0.7609706783,-1.979106936,1.691644512,2.712489961
+73.14838621,-2.352428997,-2.638553724,0.6447923505,3.593277768
+73.15842721,-3.555280779,-2.622440844,-0.4127163613,4.437065719
+73.16846721,-3.926107103,-2.628602348,-1.369938893,4.919410519
+73.17850821,-3.323647716,-2.420411942,-1.999342541,4.571914119
+73.18854821,-2.495317406,-1.762149215,-2.206071435,3.768093681
+73.19858921,-1.661745067,-1.145552869,-2.145963228,2.945988157
+73.20862921,-1.33480926,-0.8908212581,-1.919865432,2.502231314
+73.21867021,-1.71933444,-0.8792876253,-1.743411081,2.601680196
+73.22871021,-2.03183815,-1.395727453,-1.545127321,2.909267919
+73.23875121,-1.81881122,-1.770474627,-1.349895222,2.874869
+73.24879121,-1.666674124,-1.822736456,-1.491197866,2.885106912
+73.25883221,-2.135099101,-1.958366716,-1.822864217,3.422963967
+73.26887221,-2.843990676,-1.733329605,-1.759275162,3.766664782
+73.27891321,-3.4878732,-1.307853157,-1.602437636,4.055064206
+73.28895321,-3.964882036,-1.050223666,-1.180191482,4.268033651
+73.29899421,-4.082602567,-0.8300084612,-0.6184857273,4.211779002
+73.30903421,-4.182698128,-0.6795055157,-0.5192888832,4.269233224
+73.31907521,-4.767691004,-0.9091797611,-0.8961162043,4.935636697
+73.32911521,-5.597976331,-0.99833372,-1.435400811,5.8646726
+73.33915621,-6.212490045,-0.9438405937,-2.224576119,6.665928782
+73.34919621,-6.963946719,-1.323316119,-2.878971351,7.650895078
+73.35923721,-7.63991116,-1.488878276,-3.583730991,8.569021466
+73.36927721,-7.791101446,-1.211198097,-4.17777945,8.923121859
+73.37931821,-7.431226957,-0.8433322191,-4.546696658,8.75253071
+73.38935821,-6.728347197,-0.5284532243,-4.945622946,8.367144384
+73.39939921,-5.732407327,-0.2204236579,-5.586500001,8.007375514
+73.40943921,-4.747099157,0.1094961298,-6.613644122,8.141696898
+73.41948021,-4.174391866,-0.0636720854,-7.700107076,8.759066764
+73.42952021,-3.948545208,-0.6840663439,-8.518509691,9.414030135
+73.43956121,-3.963117346,-0.8441718793,-9.033334225,9.900507689
+73.44960121,-4.238290239,-0.7406574512,-9.179234535,10.13755514
+73.45964221,-4.633812278,-0.530360586,-9.156778303,10.27619032
+73.46968221,-4.838893426,-0.1725694603,-9.163490322,10.3640834
+73.47972321,-4.712068196,-0.0767979151,-8.78430248,9.968623509
+73.48976321,-3.789599175,-0.06193780124,-8.574317272,9.374636786
+73.49980421,-2.190478373,0.361127547,-8.426408443,8.713952482
+73.50984421,-0.6695998938,0.9384284109,-7.698441789,7.784280177
+73.51988521,1.295468462,1.507697539,-6.907472556,7.187806864
+73.52992521,3.211445203,2.031442586,-6.060329706,7.153162616
+73.53996621,3.896604391,2.050972871,-4.956908072,6.630305659
+73.55000621,3.04080357,1.733452104,-4.134760315,5.417341175
+73.56004721,1.704565543,1.009338765,-3.432137833,3.962811948
+73.57008721,0.8922608426,0.1193679839,-2.541482343,2.696203002
+73.58012821,0.7846455429,-0.1463213092,-2.038755113,2.18942937
+73.59016821,1.395163781,0.692556501,-1.409017004,2.100344115
+73.60020821,2.948337748,1.587818427,-0.8873278391,3.464276768
+73.61024921,4.994647756,1.705387223,-0.1357536364,5.279515209
+73.62028921,7.051596481,1.416478052,0.6370658398,7.220614648
+73.63033021,8.4933959,0.9707559121,1.330260272,8.651574039
+73.64037021,8.951000751,0.2093858689,1.431299574,9.067131595
+73.65041121,8.11128445,-0.4401438957,1.302498277,8.226977807
+73.66045121,8.093906525,-0.3215097374,6.442662181,10.35000422
+73.67049221,10.32501691,1.060969094,14.90215534,18.1605579
+73.68053221,10.1092605,1.670439,16.19504489,19.16421126
+73.69057321,8.169252577,2.868614178,19.21361383,21.07435863
+73.70061321,0.22404842,0.7472846854,13.70960401,13.73178336
+73.71065421,-3.861943266,0.3012339324,4.581477066,5.999606636
+73.72069421,-4.056839443,0.4046624064,0.8979884827,4.174695347
+73.73073521,-2.789130052,-1.095427905,-1.02233771,3.166130625
+73.74077521,-3.199443793,-1.629386283,-0.6147218746,3.642694501
+73.75081621,-3.547172737,-0.7642334247,-0.1744405693,3.632756071
+73.76085621,-3.220385303,-0.6102967018,0.6582333452,3.343144433
+73.77089721,-1.588237965,-0.5183644384,1.469687129,2.225125116
+73.78093721,-0.7079580671,0.1357378489,0.7476010197,1.038526202
+73.79097821,2.728323395,0.192444731,0.04497327447,2.735471827
+73.80101821,1.841232076,-0.2634036165,-0.03895415068,1.860385564
+73.81105921,1.269465894,-1.537765676,0.09756137788,1.996443126
+73.82109921,1.02212129,-1.925631956,0.8801036042,2.351036519
+73.83114021,1.689562026,-1.844296601,2.202076617,3.332445232
+73.84118021,2.643638755,-1.852218994,4.280053684,5.360820889
+73.85122121,0.2727036861,-1.787704325,0.2980647415,1.832783851
+73.86126121,0.5547601399,0.1317213964,-4.275559514,4.313411469
+73.87130221,1.290554754,1.061251515,-5.058048531,5.326879132
+73.88134221,3.688468657,1.161896129,-4.515208817,5.944906586
+73.89138321,4.511813924,1.520132228,-3.778289491,6.078053829
+73.90142321,3.732134202,0.1488742036,-3.441947706,5.079172496
+73.91146421,3.069911594,-0.8030881727,-2.964098625,4.342256149
+73.92150421,2.085738661,-0.7724370682,-2.777937897,3.558637906
+73.93154521,2.777754294,-0.2865539128,-2.451389029,3.715822955
+73.94158521,2.754242055,0.3672068971,-2.153763413,3.515591991
+73.95162621,1.484837557,0.369389078,-2.018978661,2.533271737
+73.96166621,0.353357913,-0.7958019572,-2.171714365,2.339766197
+73.97170721,-0.4037783805,-1.710062656,-1.888643054,2.579597615
+73.98174721,-1.282434433,-2.124680532,-0.3362412125,2.504388866
+73.99178821,-2.033560739,-2.633678901,2.593285165,4.218620839
+74.00182821,-1.075018345,-3.644692892,4.716004542,6.056413919
+74.01186921,1.64461828,-3.327400752,4.351332412,5.719305798
+74.02190921,3.747336085,-0.9663915503,3.404771694,5.154503919
+74.03195021,2.634037043,-0.457170403,2.561738852,3.702656056
+74.04199021,-0.753567884,0.3860208982,2.05407248,2.221731406
+74.05203121,-2.722161307,1.288932152,1.525193578,3.376051499
+74.06207121,-0.2678807565,0.4257246619,2.023020256,2.084613284
+74.07211221,0.1154787815,-0.5140877849,2.076908196,2.142701391
+74.08215221,-0.1193451067,-0.8599576074,1.9094837,2.097593465
+74.09219221,0.4912049988,-0.6856135172,1.16780708,1.440528244
+74.10223321,1.352393737,-0.4983616984,-0.2803020698,1.46829917
+74.11227321,1.278411841,-0.145616135,0.1247170168,1.292708486
+74.12231421,0.398926361,-0.3325937194,0.6701031929,0.8478202126
+74.13235421,-0.776580186,-0.3573771429,2.001137636,2.176085257
+74.14239521,-1.66642781,-0.1237639207,2.509392824,3.014855137
+74.15243479,-2.247666042,0.5458843589,2.993323594,3.782853223
+74.16247579,-3.32967795,0.7989506829,4.675668694,5.795425366
+74.17251579,-2.083074669,0.07377958238,2.507029964,3.260343961
+74.18255679,-0.597656191,0.0803173542,0.2045554841,0.6367784121
+74.19259679,-1.17288831,0.6072590733,1.00839327,1.661712236
+74.20263779,-1.832337437,0.1132687533,1.44465403,2.336089801
+74.21267779,-1.856026701,-0.3642686713,1.691570252,2.537505999
+74.22271879,-1.026558376,-0.6694395339,1.817687677,2.192249959
+74.23275879,0.5834913111,-0.7077598464,0.9845570952,1.345636944
+74.24279979,1.361814771,-0.6856556171,0.4518307257,1.590224544
+74.25283979,1.17302455,-1.025756577,0.5201788294,1.642787011
+74.26288079,0.3621452549,-0.976176281,0.4748371804,1.144351198
+74.27292079,-0.9196303435,-0.7269679499,0.08967816174,1.175688965
+74.28296179,-1.790190707,-0.6633116519,-0.2105249065,1.920699313
+74.29300179,-1.875923168,-0.6071754581,0.192356438,1.981098374
+74.30304279,-1.611999441,-0.5623448557,0.459190616,1.767945123
+74.31308279,-0.8858075631,-0.7478360778,0.4887675869,1.258096813
+74.32312379,0.7573613383,-0.8202193451,0.7663419306,1.354118136
+74.33316379,1.263265945,-0.6036694676,1.112814601,1.788466944
+74.34320479,0.2954827572,-0.5423397768,1.611906617,1.726176536
+74.35324479,0.2137015526,-0.07915492773,0.9090496606,0.937179354
+74.36328579,0.5397539918,-0.07435085535,-0.03178020179,0.5457768799
+74.37332579,0.2241133972,-0.7514426404,0.03423076987,0.7848978292
+74.38336679,-0.2882756254,-1.233933826,0.2319344866,1.288211601
+74.39340679,-0.4411135103,-1.281294519,0.4386095864,1.424315675
+74.40344779,-0.1850364549,-1.073621299,0.3401991928,1.141331098
+74.41348779,0.554659714,-0.551434536,0.3677460104,0.8642711229
+74.42352879,1.234501152,-0.002488574982,1.26051176,1.764338172
+74.43356879,1.390911247,0.03601475537,2.167982088,2.576058519
+74.44360979,1.369569641,-0.1128840065,1.829460461,2.288097327
+74.45364979,1.097578657,-0.3025676823,0.8188160133,1.402385744
+74.46369079,0.2801683147,-1.021529624,0.2098922378,1.079848049
+74.47373079,-0.4020391993,-2.384341931,-0.1582911444,2.423175199
+74.48377179,-0.1517131729,-1.080516336,-0.6687390375,1.279743857
+74.49381179,-0.7199020283,-1.287769725,-0.07759255171,1.477372803
+74.50385279,-1.004627809,-2.132322843,0.2201558554,2.367392309
+74.51389279,-0.4539865941,-1.560849899,0.9651244587,1.890455357
+74.52393379,-0.599314169,-1.637979351,1.161392099,2.095467832
+74.53397379,-0.04426956207,-1.787173398,2.665985937,3.209895569
+74.54401379,1.622833016,-0.6582807076,-1.01770613,2.025499014
+74.55405479,3.023266308,0.3157742035,-2.510085719,3.942129226
+74.56409579,2.34909433,0.702802577,-0.5675786984,2.516807743
+74.57413579,0.963015368,0.8835645711,0.8379714918,1.552508026
+74.58417579,0.2298087314,0.8602955765,1.249889708,1.534648108
+74.59421679,-0.4356713605,0.3189767236,0.3383122963,0.6371898417
+74.60425679,-0.6161234522,0.004526329637,0.30138596,0.6859023931
+74.61429779,-0.2170536152,-0.1531415015,0.1148609501,0.2894091035
+74.62433779,0.4082979128,-0.3900706798,-0.685128783,0.8878421989
+74.63437879,0.9006670922,-0.2310176432,0.3177926624,0.9826304182
+74.64441879,1.240368687,0.2806833082,0.6763076735,1.440378307
+74.65445979,1.350060698,0.4288844973,0.3028290528,1.448554879
+74.66449979,1.146795987,0.3426211095,0.05452762485,1.198125003
+74.67454079,0.7988644364,0.04778870881,-0.06312127769,0.8027779545
+74.68458079,0.5105201063,-0.3347063184,0.1528275061,0.6292975012
+74.69462179,0.008847422004,-0.5793514824,0.5158822954,0.7757969836
+74.70466179,-0.3045914036,-0.8609440327,0.9410245746,1.311307668
+74.71470279,-0.4664265454,-1.198789721,1.449548149,1.937999059
+74.72474279,-0.555115943,-1.420801483,1.7629133,2.331242987
+74.73478379,-0.1672154573,-1.485255341,2.33400559,2.771556698
+74.74482379,-0.1955098414,-1.61852508,3.242133729,3.628950076
+74.75486479,-0.1022271636,-1.342686775,3.425478439,3.680646778
+74.76490479,-0.1369885683,-1.106305481,2.68186522,2.904320702
+74.77494579,-0.1304581055,-0.8418090194,1.61606808,1.826838193
+74.78498579,0.07072733581,-0.6968857795,0.3605100811,0.7877941763
+74.79502679,-0.2921266016,-0.6328733861,-0.6244317609,0.9358320887
+74.80506679,-0.6227360684,-0.5313347322,-1.253100414,1.496789049
+74.81510779,-0.7688103327,-0.5488044584,-1.449075694,1.729761842
+74.82514779,-0.6973260748,-0.5734586585,-1.014528168,1.358081696
+74.83518879,-0.2855601785,-0.4611739916,-0.09434482455,0.5505697158
+74.84522879,0.03055988789,-0.3608521432,0.8628882319,0.9358014088
+74.85526979,0.4307053202,-0.26037242,1.820976151,1.889247208
+74.86530979,0.8211753649,-0.1801129532,2.777025731,2.901489543
+74.87535079,0.9110304049,-0.3649294066,3.25686345,3.401515751
+74.88539079,0.7120844471,-0.6429364443,3.110813452,3.255394272
+74.89543179,0.4180080914,-0.7979502243,2.552647601,2.706929091
+74.90547179,0.1644453388,-0.7356598359,1.909028202,2.052468353
+74.91551279,0.1525062016,-0.6397964895,1.301248727,1.458028099
+74.92555279,0.3425205374,-0.5757139295,0.6297334313,0.9194188609
+74.93559379,0.4182609835,-0.2651969576,0.1009808296,0.5054392195
+74.94563379,0.5472786275,-0.1780366069,-0.316947155,0.6570132636
+74.95567479,0.4787834662,-0.1696271414,-0.4656441879,0.6890801727
+74.96571479,0.3111323914,-0.2241687995,-0.4423985821,0.5854669257
+74.97575579,0.151544627,-0.4530656576,-0.2439440829,0.5364167966
+74.98579579,-0.05319855273,-0.5915628076,-0.1279756701,0.6075807876
+74.99583679,-0.1173819771,-0.7390558988,-0.02588913202,0.7487672517
+75.00587679,-0.1818466526,-0.9148161846,0.007217803001,0.9327427048
+75.01591779,-0.2337357214,-0.9399083412,-0.007409006953,0.968563354
+75.02595779,-0.09143349588,-0.8675975794,0.07475957572,0.8755995877
+75.03599779,0.1099934354,-0.7554281026,-0.002991435528,0.7633997136
+75.04603879,0.1513586855,-0.6487865835,-0.1762549603,0.6891293737
+75.05607879,0.1187025708,-0.6373061603,-0.2285238057,0.6873664031
+75.06611979,-0.00684387356,-0.7658238673,-0.1833417857,0.7874942824
+75.07615979,-0.2217588696,-0.9485405856,0.01688734353,0.974264554
+75.08620079,-0.3786528218,-1.009233515,0.3391776842,1.130031746
+75.09624079,-0.3976320067,-1.116635756,0.5057069707,1.288691649
+75.10628179,-0.3443536395,-1.145766,0.7011910844,1.386732884
+75.11632179,-0.2453102848,-1.022036578,0.9226146162,1.398554122
+75.12636279,-0.05805963546,-0.8518305624,1.044717343,1.349229615
+75.13640279,0.1966021013,-0.7256926721,0.9293202031,1.195373699
+75.14644379,0.2706889549,-0.6271530551,0.7175808299,0.9907147481
+75.15648392,0.1723922896,-0.5002164352,0.5438811028,0.7587768035
+75.16652492,0.01059544712,-0.4126578891,0.565483641,0.7001218074
+75.17656492,-0.06828466147,-0.4110376257,0.6801867163,0.7976645246
+75.18660592,-0.1692058495,-0.5044585901,0.9050466567,1.049865963
+75.19664592,-0.08104182422,-0.6273378271,1.245935236,1.397309965
+75.20668692,0.1930431935,-0.5932614237,1.773278074,1.879824439
+75.21672692,0.4099006346,-0.5324047726,2.064695701,2.171276516
+75.22676792,0.5304775304,-0.4603454411,1.973078018,2.094364152
+75.23680792,0.6075993812,-0.4167924553,1.510814105,1.680908153
+75.24684892,0.439141683,-0.4167000693,0.8948619765,1.08039915
+75.25688892,0.2070928833,-0.4589602357,0.411904183,0.6505359454
+75.26692992,-0.03815863699,-0.5331742662,-0.2690087575,0.5984117239
+75.27696992,-0.3738680452,-0.6152036852,-1.37387173,1.55105655
+75.28701092,-0.4725401017,-0.6538058335,-1.060253395,1.332251281
+75.29705092,-0.3510940173,-0.7009022319,-0.2212533778,0.8145452749
+75.30709192,-0.3793769994,-0.6443345135,0.7804109162,1.080802975
+75.31713192,-0.2294885963,-0.4705219352,1.879322593,1.950873987
+75.32717292,0.1104831398,-0.2909767467,2.280228163,2.301372301
+75.33721292,0.1329995978,-0.2115241957,2.018614379,2.034019516
+75.34725392,-0.02996376425,-0.1949450004,1.260234017,1.275574835
+75.35729392,0.02831952721,-0.05004573405,0.6245703399,0.6272118307
\ No newline at end of file
diff --git a/testing/racing_logs/gg_data/behavior.json b/testing/racing_logs/gg_data/behavior.json
new file mode 100644
index 000000000..45ef236d6
--- /dev/null
+++ b/testing/racing_logs/gg_data/behavior.json
@@ -0,0 +1,6974 @@
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059565.3292518, "x": -88.23581459663751, "y": 40.09286990231887, "z": 201.13365679287222, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5572338162215615, "steering_wheel_angle": -1.939, "front_wheel_angle": -0.09143150745836416, "heading_rate": -0.001432611608223352, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059565.3283975}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.04, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.939, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059565.3283975}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059565.4296944, "x": -88.23581459663751, "y": 40.09286990231887, "z": 201.13365679287222, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5572338162215615, "steering_wheel_angle": -2.086, "front_wheel_angle": -0.09856918585864004, "heading_rate": -0.0015451509426858052, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059565.4295576}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.04, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.086, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059565.4295576}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059565.530282, "x": -88.23581459663751, "y": 40.09286990231887, "z": 201.13365679287222, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5567268162215617, "steering_wheel_angle": -2.269, "front_wheel_angle": -0.10749813009545346, "heading_rate": -0.001264618716160161, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059565.5297575}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.269, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059565.5297575}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059565.6298153, "x": -88.23581467013179, "y": 40.09286973284862, "z": 201.12887842402952, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5567268162215617, "steering_wheel_angle": -2.476, "front_wheel_angle": -0.11765684484421653, "heading_rate": -0.001385188841646568, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059565.6297035}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.476, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059565.6297035}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059565.7298172, "x": -88.23581467013179, "y": 40.09286973284862, "z": 201.12887842402952, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5567268162215617, "steering_wheel_angle": -2.693, "front_wheel_angle": -0.1283745174710267, "heading_rate": -0.0015127078375209132, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059565.729679}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.693, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059565.729679}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059565.8298202, "x": -88.23581467013179, "y": 40.09286973284862, "z": 201.12887842402952, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5567268162215617, "steering_wheel_angle": -2.881, "front_wheel_angle": -0.13771736730926432, "heading_rate": -0.0016241563606781157, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059565.8297033}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.881, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059565.8297033}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059565.9300299, "x": -88.23581467013179, "y": 40.09286973284862, "z": 201.12887842402952, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5567268162215617, "steering_wheel_angle": -2.975, "front_wheel_angle": -0.14240911618184793, "heading_rate": -0.0016802307766661862, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059565.9297175}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.975, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059565.9297175}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059566.0298357, "x": -88.23581467013179, "y": 40.09286973284862, "z": 201.12887842402952, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5567268162215617, "steering_wheel_angle": -3.063, "front_wheel_angle": -0.1468138124340309, "heading_rate": -0.001732943081567325, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059566.0297031}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.063, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059566.0297031}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059566.1298528, "x": -88.235814783193, "y": 40.092869559988706, "z": 201.12819128940606, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5562218162215617, "steering_wheel_angle": -3.18, "front_wheel_angle": -0.15268883112395087, "heading_rate": -0.001202238998409709, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059566.129713}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059566.129713}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059566.2300615, "x": -88.235814783193, "y": 40.092869559988706, "z": 201.12819128940606, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5562218162215617, "steering_wheel_angle": -3.333, "front_wheel_angle": -0.16040424941210663, "heading_rate": -0.0012640176971228526, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059566.229758}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.333, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059566.229758}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059566.329862, "x": -88.235814783193, "y": 40.092869559988706, "z": 201.12819128940606, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5562218162215617, "steering_wheel_angle": -3.487, "front_wheel_angle": -0.16820802624476353, "heading_rate": -0.0013266610258909975, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059566.3297145}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.487, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059566.3297145}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059566.4300227, "x": -88.235814783193, "y": 40.092869559988706, "z": 201.12819128940606, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5562218162215617, "steering_wheel_angle": -3.64, "front_wheel_angle": -0.175999370903955, "heading_rate": -0.0013893704073064583, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059566.429747}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.64, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059566.429747}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059566.529876, "x": -88.235814783193, "y": 40.092869559988706, "z": 201.12819128940606, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5562218162215617, "steering_wheel_angle": -3.749, "front_wheel_angle": -0.18157363141365024, "heading_rate": -0.00143434167952862, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059566.5297117}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.749, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059566.5297117}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059566.6298006, "x": -88.23581482394248, "y": 40.09286949705231, "z": 201.1332235620361, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5562218162215617, "steering_wheel_angle": -3.858, "front_wheel_angle": -0.1871677360903278, "heading_rate": -0.0014795656875650467, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059566.6297007}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.858, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059566.6297007}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059566.7299178, "x": -88.23581482394248, "y": 40.09286949705231, "z": 201.1332235620361, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5562218162215617, "steering_wheel_angle": -3.947, "front_wheel_angle": -0.19175026455499836, "heading_rate": -0.0015166832188626943, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059566.729683}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.947, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059566.729683}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059566.8298557, "x": -88.23581482394248, "y": 40.09286949705231, "z": 201.1332235620361, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5562218162215617, "steering_wheel_angle": -4.057, "front_wheel_angle": -0.19743271731281645, "heading_rate": -0.0015628019066301082, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059566.8297026}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.057, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059566.8297026}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059566.9300365, "x": -88.23581482394248, "y": 40.09286949705231, "z": 201.1332235620361, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5562218162215617, "steering_wheel_angle": -4.171, "front_wheel_angle": -0.2033437922813402, "heading_rate": -0.0016108875232278277, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059566.9297762}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.171, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059566.9297762}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059567.0298164, "x": -88.23581482394248, "y": 40.09286949705231, "z": 201.1332235620361, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5562218162215617, "steering_wheel_angle": -4.281, "front_wheel_angle": -0.2090689151681466, "heading_rate": -0.0016575722929439243, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059567.0296974}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.281, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059567.0296974}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059567.1298237, "x": -88.23581484744301, "y": 40.09286943746179, "z": 201.1299764896105, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5562218162215617, "steering_wheel_angle": -4.343, "front_wheel_angle": -0.21230517743251215, "heading_rate": -0.0016840119863463265, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059567.129694}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.343, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059567.129694}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059567.2303877, "x": -88.23581484744301, "y": 40.09286943746179, "z": 201.1299764896105, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5557188162215616, "steering_wheel_angle": -4.383, "front_wheel_angle": -0.21439670111767595, "heading_rate": -0.0008505594822990146, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059567.2297564}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.383, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059567.2297564}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059567.3299687, "x": -88.23581484744301, "y": 40.09286943746179, "z": 201.1299764896105, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5557188162215616, "steering_wheel_angle": -4.446, "front_wheel_angle": -0.2176966287525443, "heading_rate": -0.0008640707403721332, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059567.3297105}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.446, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059567.3297105}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059567.4298222, "x": -88.23581484744301, "y": 40.09286943746179, "z": 201.1299764896105, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5557188162215616, "steering_wheel_angle": -4.484, "front_wheel_angle": -0.21969049512482441, "heading_rate": -0.0008722439927065224, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059567.4297137}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.484, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059567.4297137}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059567.5298111, "x": -88.23581484744301, "y": 40.09286943746179, "z": 201.1299764896105, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5557188162215616, "steering_wheel_angle": -4.489, "front_wheel_angle": -0.21995303901975063, "heading_rate": -0.0008733207528987105, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059567.5297015}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.489, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059567.5297015}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059567.6298382, "x": -88.23581490041411, "y": 40.092869347411714, "z": 201.12524692030033, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5557188162215616, "steering_wheel_angle": -4.48, "front_wheel_angle": -0.21948049237223594, "heading_rate": -0.0008713828081653323, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059567.6297045}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.48, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059567.6297045}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059567.7299242, "x": -88.23581490041411, "y": 40.092869347411714, "z": 201.12524692030033, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5557188162215616, "steering_wheel_angle": -4.427, "front_wheel_angle": -0.21670066597324056, "heading_rate": -0.0008599907956459491, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059567.729723}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.427, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059567.729723}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059567.8298645, "x": -88.23581490041411, "y": 40.092869347411714, "z": 201.12524692030033, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5557188162215616, "steering_wheel_angle": -4.323, "front_wheel_angle": -0.21126047961564912, "heading_rate": -0.0008377364923106838, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059567.82968}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.323, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059567.82968}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059567.929858, "x": -88.23581490041411, "y": 40.092869347411714, "z": 201.12524692030033, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5557188162215616, "steering_wheel_angle": -4.266, "front_wheel_angle": -0.20828696711668174, "heading_rate": -0.000825594690682266, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059567.9297101}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.266, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059567.9297101}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059568.0297787, "x": -88.23581490041411, "y": 40.092869347411714, "z": 201.12524692030033, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5557188162215616, "steering_wheel_angle": -4.261, "front_wheel_angle": -0.20802640571473488, "heading_rate": -0.0008245314655393115, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059568.029671}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.261, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059568.029671}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059568.1299329, "x": -88.23581499374808, "y": 40.09286929652231, "z": 201.13258325715552, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5557188162215616, "steering_wheel_angle": -4.257, "front_wheel_angle": -0.20781798822902223, "heading_rate": -0.0008236810987066937, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059568.1296835}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.257, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059568.1296835}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059568.2298126, "x": -88.23581499374808, "y": 40.09286929652231, "z": 201.13258325715552, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5557188162215616, "steering_wheel_angle": -4.256, "front_wheel_angle": -0.20776588824997969, "heading_rate": -0.0008234685366001105, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059568.2297025}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.256, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059568.2297025}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059568.3297951, "x": -88.23581499374808, "y": 40.09286929652231, "z": 201.13258325715552, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5557188162215616, "steering_wheel_angle": -4.256, "front_wheel_angle": -0.20776588824997969, "heading_rate": -0.0008234685366001105, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059568.3296967}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.256, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059568.3296967}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059568.429887, "x": -88.23581499374808, "y": 40.09286929652231, "z": 201.13258325715552, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5557188162215616, "steering_wheel_angle": -4.256, "front_wheel_angle": -0.20776588824997969, "heading_rate": -0.0008234685366001105, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059568.4296997}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.256, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059568.4296997}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059568.5297754, "x": -88.23581499374808, "y": 40.09286929652231, "z": 201.13258325715552, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -4.256, "front_wheel_angle": -0.20776588824997969, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059568.5296688}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.256, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059568.5296688}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059568.6297822, "x": -88.23581505207227, "y": 40.092869253512575, "z": 201.1319079905467, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -4.257, "front_wheel_angle": -0.20781798822902223, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059568.6296697}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.257, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059568.6296697}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059568.7298112, "x": -88.23581505207227, "y": 40.092869253512575, "z": 201.1319079905467, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -4.256, "front_wheel_angle": -0.20776588824997969, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059568.7296743}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.256, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059568.7296743}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059568.829864, "x": -88.23581505207227, "y": 40.092869253512575, "z": 201.1319079905467, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5557188162215616, "steering_wheel_angle": -4.257, "front_wheel_angle": -0.20781798822902223, "heading_rate": -0.0008236810987066937, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059568.8297157}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.257, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059568.8297157}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059568.9298813, "x": -88.23581505207227, "y": 40.092869253512575, "z": 201.1319079905467, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5557188162215616, "steering_wheel_angle": -4.259, "front_wheel_angle": -0.20792219345761434, "heading_rate": -0.0008241062584367324, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059568.9297333}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059568.9297333}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059569.0297759, "x": -88.23581505207227, "y": 40.092869253512575, "z": 201.1319079905467, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -4.273, "front_wheel_angle": -0.20865182693623402, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059569.0296702}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059569.0296702}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059569.1298625, "x": -88.23581509113714, "y": 40.092869245372185, "z": 201.13408569194507, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -4.294, "front_wheel_angle": -0.20974692396899247, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059569.1296835}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.294, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059569.1296835}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059569.229809, "x": -88.23581509113714, "y": 40.092869245372185, "z": 201.13408569194507, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5557188162215616, "steering_wheel_angle": -4.323, "front_wheel_angle": -0.21126047961564912, "heading_rate": -0.0008377364923106838, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059569.2296946}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.323, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059569.2296946}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059569.3298855, "x": -88.23581509113714, "y": 40.092869245372185, "z": 201.13408569194507, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.561886816221562, "steering_wheel_angle": -4.358, "front_wheel_angle": -0.2130891659113922, "heading_rate": -0.010987746670384713, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059569.3297234}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.358, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059569.3297234}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059569.4298155, "x": -88.23581509113714, "y": 40.092869245372185, "z": 201.13408569194507, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5728068162215614, "steering_wheel_angle": -4.358, "front_wheel_angle": -0.2130891659113922, "heading_rate": -0.027891972317130424, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059569.429678}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.358, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059569.429678}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059569.5298889, "x": -88.23581509113714, "y": 40.092869245372185, "z": 201.13408569194507, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5608388162215614, "steering_wheel_angle": -4.439, "front_wheel_angle": -0.21732961994566383, "heading_rate": -0.009488237948898373, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059569.5297706}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.11, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.439, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059569.5297706}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059569.6301007, "x": -88.2358151848011, "y": 40.09286914683875, "z": 201.1333495851568, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5700018162215614, "steering_wheel_angle": -4.439, "front_wheel_angle": -0.21732961994566383, "heading_rate": -0.024151878415377675, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059569.6297598}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.439, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059569.6297598}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059569.7301636, "x": -88.2358151848011, "y": 40.09286914683875, "z": 201.1333495851568, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.559281816221562, "steering_wheel_angle": -4.482, "front_wheel_angle": -0.21958549015346385, "heading_rate": -0.006974507004819279, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059569.7297251}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.482, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059569.7297251}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059569.8297846, "x": -88.2358151848011, "y": 40.09286914683875, "z": 201.1333495851568, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5705588162215616, "steering_wheel_angle": -4.716, "front_wheel_angle": -0.23192026228705537, "heading_rate": -0.026753611630472802, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059569.8296924}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.29, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.716, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059569.8296924}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059569.9300807, "x": -88.2358151848011, "y": 40.09286914683875, "z": 201.1333495851568, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5762388162215615, "steering_wheel_angle": -4.716, "front_wheel_angle": -0.23192026228705537, "heading_rate": -0.0359789949513255, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059569.9297895}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.39, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.716, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059569.9297895}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059570.0297997, "x": -88.2358151848011, "y": 40.09286914683875, "z": 201.1333495851568, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5745138162215615, "steering_wheel_angle": -5.043, "front_wheel_angle": -0.24932680399593793, "heading_rate": -0.03580663448120592, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059570.0296705}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.043, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059570.0296705}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059570.1297662, "x": -88.23581523330603, "y": 40.09286812007795, "z": 202.7980063881853, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5888178162215616, "steering_wheel_angle": -5.253, "front_wheel_angle": -0.2606123709226447, "heading_rate": -0.0625025051954669, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059570.1296666}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.253, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059570.1296666}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059570.2298071, "x": -88.23581523330603, "y": 40.09286812007795, "z": 202.7980063881853, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5851338162215614, "steering_wheel_angle": -5.253, "front_wheel_angle": -0.2606123709226447, "heading_rate": -0.056252254675920224, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059570.2296698}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.54, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.494, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059570.2296698}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059570.3298059, "x": -88.23581523330603, "y": 40.09286812007795, "z": 202.7980063881853, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5976938162215615, "steering_wheel_angle": -5.494, "front_wheel_angle": -0.27366999820303933, "heading_rate": -0.08114368042710325, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059570.329671}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.494, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059570.329671}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059570.430022, "x": -88.23581523330603, "y": 40.09286812007795, "z": 202.7980063881853, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6036068162215615, "steering_wheel_angle": -5.775, "front_wheel_angle": -0.28904192755689995, "heading_rate": -0.09641283096088091, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059570.42968}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.775, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059570.42968}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059570.5297968, "x": -88.23581523330603, "y": 40.09286812007795, "z": 202.7980063881853, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6016178162215615, "steering_wheel_angle": -6.083, "front_wheel_angle": -0.3060784668394318, "heading_rate": -0.09875280850360527, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059570.529672}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.083, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059570.529672}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059570.6298187, "x": -88.23581501785382, "y": 40.09286505568139, "z": 202.7868971846393, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.615217816221562, "steering_wheel_angle": -6.465, "front_wheel_angle": -0.32749103859493667, "heading_rate": -0.13270466707550874, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059570.629677}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.465, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059570.629677}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059570.7297654, "x": -88.23581501785382, "y": 40.09286505568139, "z": 202.7868971846393, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6062868162215613, "steering_wheel_angle": -6.782, "front_wheel_angle": -0.3455074190589632, "heading_rate": -0.12232526171397408, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059570.7296658}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.782, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059570.7296658}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059570.8298001, "x": -88.23581501785382, "y": 40.09286505568139, "z": 202.7868971846393, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6187428162215616, "steering_wheel_angle": -7.011, "front_wheel_angle": -0.3586672282667436, "heading_rate": -0.15376020189167228, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059570.82967}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.011, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059570.82967}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059570.92984, "x": -88.23581501785382, "y": 40.09286505568139, "z": 202.7868971846393, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6131268162215617, "steering_wheel_angle": -7.205, "front_wheel_angle": -0.3699136806053126, "heading_rate": -0.14692615003376971, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059570.9297311}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.205, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059570.9297311}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059571.0298104, "x": -88.23581501785382, "y": 40.09286505568139, "z": 202.7868971846393, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6103668162215614, "steering_wheel_angle": -7.41, "front_wheel_angle": -0.38189805952973377, "heading_rate": -0.14589929069804142, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059571.0296712}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.41, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059571.0296712}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059571.1298296, "x": -88.23581475049882, "y": 40.09286040159468, "z": 202.80530940384747, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6069618162215615, "steering_wheel_angle": -7.572, "front_wheel_angle": -0.3914432582613193, "heading_rate": -0.14188041926464634, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059571.1297073}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.88, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.572, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059571.1297073}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059571.2297769, "x": -88.23581475049882, "y": 40.09286040159468, "z": 202.80530940384747, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6208818162215617, "steering_wheel_angle": -7.647, "front_wheel_angle": -0.3958850673566466, "heading_rate": -0.17632312949822854, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059571.2296674}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.647, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059571.2296674}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059571.3298244, "x": -88.23581475049882, "y": 40.09286040159468, "z": 202.80530940384747, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6495338162215614, "steering_wheel_angle": -7.647, "front_wheel_angle": -0.3958850673566466, "heading_rate": -0.2383627491364941, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059571.3297012}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.647, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059571.3297012}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059571.4298089, "x": -88.23581475049882, "y": 40.09286040159468, "z": 202.80530940384747, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5913138162215614, "steering_wheel_angle": -7.638, "front_wheel_angle": -0.39535128295014854, "heading_rate": -0.10433105850681183, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059571.4297016}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059571.4297016}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059571.5297623, "x": -88.23581475049882, "y": 40.09286040159468, "z": 202.80530940384747, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.614518816221562, "steering_wheel_angle": -7.635, "front_wheel_angle": -0.39517340144645574, "heading_rate": -0.16130634155685056, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059571.5296636}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.635, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059571.5296636}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059571.6297972, "x": -88.23581424812438, "y": 40.09285549590891, "z": 202.81370969292055, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6371178162215614, "steering_wheel_angle": -7.624, "front_wheel_angle": -0.39452136854650166, "heading_rate": -0.21142779495045336, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059571.6296687}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.624, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059571.6296687}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059571.7298152, "x": -88.23581424812438, "y": 40.09285549590891, "z": 202.81370969292055, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6069618162215615, "steering_wheel_angle": -7.575, "front_wheel_angle": -0.39162065236615506, "heading_rate": -0.1419517919410313, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059571.7296972}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.88, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.575, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059571.7296972}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059571.8297882, "x": -88.23581424812438, "y": 40.09285549590891, "z": 202.81370969292055, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5976938162215615, "steering_wheel_angle": -7.439, "front_wheel_angle": -0.38360187874400226, "heading_rate": -0.11666425051093272, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059571.8296692}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.439, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059571.8296692}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059571.9298537, "x": -88.23581424812438, "y": 40.09285549590891, "z": 202.81370969292055, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.631846816221562, "steering_wheel_angle": -7.108, "front_wheel_angle": -0.36427906938308935, "heading_rate": -0.18320085426585112, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059571.9296756}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.108, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059571.9296756}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059572.029984, "x": -88.23581424812438, "y": 40.09285549590891, "z": 202.81370969292055, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6311018162215616, "steering_wheel_angle": -6.671, "front_wheel_angle": -0.3391727230971709, "heading_rate": -0.16813427915250917, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059572.0297208}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.671, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059572.0297208}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059572.1297755, "x": -88.23581424812438, "y": 40.09285549590891, "z": 202.81370969292055, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6117428162215615, "steering_wheel_angle": -6.198, "front_wheel_angle": -0.31249117215030564, "heading_rate": -0.11989166808022117, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059572.1296666}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.198, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059572.1296666}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059572.22976, "x": -88.2358132166781, "y": 40.092850815011154, "z": 202.79277105525287, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6003018162215614, "steering_wheel_angle": -5.748, "front_wheel_angle": -0.2875579069720304, "heading_rate": -0.09011289914253588, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059572.2296622}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.78, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.748, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059572.2296622}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059572.329932, "x": -88.2358132166781, "y": 40.092850815011154, "z": 202.79277105525287, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6003018162215614, "steering_wheel_angle": -5.338, "front_wheel_angle": -0.2652046761610288, "heading_rate": -0.08275383092753594, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059572.3297124}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.78, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.338, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059572.3297124}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059572.4298635, "x": -88.2358132166781, "y": 40.092850815011154, "z": 202.79277105525287, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6252138162215615, "steering_wheel_angle": -5.168, "front_wheel_angle": -0.2560341538414691, "heading_rate": -0.11657368173534381, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059572.4296792}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.14, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.168, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059572.4296792}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059572.5299795, "x": -88.2358132166781, "y": 40.092850815011154, "z": 202.79277105525287, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6201668162215617, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.10970397948547228, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059572.5296805}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059572.5296805}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059572.6297698, "x": -88.23581167502846, "y": 40.09284643977215, "z": 202.82670487489239, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6138218162215616, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.10047654195865685, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059572.6296706}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059572.6296706}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059572.7298284, "x": -88.23581167502846, "y": 40.09284643977215, "z": 202.82670487489239, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6076388162215616, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.09124910443184142, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059572.7296777}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059572.7296777}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059572.8301988, "x": -88.23581167502846, "y": 40.09284643977215, "z": 202.82670487489239, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6029418162215614, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.08407220857765164, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059572.8297243}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059572.8297243}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059572.9297798, "x": -88.23581167502846, "y": 40.09284643977215, "z": 202.82670487489239, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5989938162215616, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.0779205835597747, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059572.929665}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.76, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059572.929665}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059573.0297558, "x": -88.23581167502846, "y": 40.09284643977215, "z": 202.82670487489239, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6173268162215617, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.10560289614022096, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059573.029663}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059573.029663}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059573.129799, "x": -88.23580977139132, "y": 40.09284227246025, "z": 202.8164172817411, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.615217816221562, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.10252708363128249, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059573.1296957}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059573.1296957}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059573.2298172, "x": -88.23580977139132, "y": 40.09284227246025, "z": 202.8164172817411, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6110538162215615, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.09637545861340553, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059573.2296944}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.94, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059573.2296944}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059573.3299134, "x": -88.23580977139132, "y": 40.09284227246025, "z": 202.8164172817411, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6056138162215614, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.08817329192290295, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059573.329678}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.86, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059573.329678}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059573.4298637, "x": -88.23580977139132, "y": 40.09284227246025, "z": 202.8164172817411, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6016178162215615, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.08202166690502599, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059573.4296775}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059573.4296775}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059573.5301547, "x": -88.23580977139132, "y": 40.09284227246025, "z": 202.8164172817411, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5989938162215616, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.0779205835597747, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059573.5296965}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.76, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059573.5296965}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059573.629799, "x": -88.2358077431814, "y": 40.092838269006215, "z": 202.82428752265218, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6131268162215617, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.09945127112234403, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059573.629669}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059573.629669}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059573.7297976, "x": -88.2358077431814, "y": 40.092838269006215, "z": 202.82428752265218, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6083178162215614, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.09227437526815424, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059573.7296681}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.88, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059573.7296681}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059573.829792, "x": -88.2358077431814, "y": 40.092838269006215, "z": 202.82428752265218, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6003018162215614, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.07997112523240035, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059573.8296673}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.78, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059573.8296673}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059573.9297912, "x": -88.2358077431814, "y": 40.092838269006215, "z": 202.82428752265218, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5944788162215615, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.07074368770558491, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059573.9296682}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059573.9296682}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059574.0301757, "x": -88.2358077431814, "y": 40.092838269006215, "z": 202.82428752265218, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6036068162215615, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.08509747941396446, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059574.0296903}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059574.0296903}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059574.129858, "x": -88.23580582656135, "y": 40.092834697394224, "z": 202.83615676016535, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5925738162215617, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.06766787519664645, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059574.1297278}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059574.1297278}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059574.2299774, "x": -88.23580582656135, "y": 40.092834697394224, "z": 202.83615676016535, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5976938162215615, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.07587004188714905, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059574.2296855}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059574.2296855}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059574.3297763, "x": -88.23580582656135, "y": 40.092834697394224, "z": 202.83615676016535, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5925738162215617, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.06766787519664645, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059574.3296685}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059574.3296685}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059574.430439, "x": -88.23580582656135, "y": 40.092834697394224, "z": 202.83615676016535, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5925738162215617, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.06766787519664645, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059574.4301636}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.73, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059574.4301636}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059574.5298371, "x": -88.23580582656135, "y": 40.092834697394224, "z": 202.83615676016535, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.593206816221562, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.06869314603295928, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059574.5297024}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059574.5297024}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059574.6299038, "x": -88.23580385758787, "y": 40.09283170406734, "z": 202.81136599032754, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.589438816221562, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.06254152101508233, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059574.6297743}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059574.6297743}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059574.7298644, "x": -88.23580385758787, "y": 40.09283170406734, "z": 202.81136599032754, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5888178162215616, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.0615162501787695, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059574.7296822}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059574.7296822}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059574.8297954, "x": -88.23580385758787, "y": 40.09283170406734, "z": 202.81136599032754, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5857428162215617, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.056389895997205376, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059574.8296692}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.55, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059574.8296692}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059574.9299738, "x": -88.23580385758787, "y": 40.09283170406734, "z": 202.81136599032754, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5857428162215617, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.056389895997205376, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059574.9296708}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.55, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059574.9296708}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059575.0298357, "x": -88.23580385758787, "y": 40.09283170406734, "z": 202.81136599032754, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5827178162215616, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.051263541815641245, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059575.0297074}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059575.0297074}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059575.1298277, "x": -88.23580199183341, "y": 40.092829274070674, "z": 202.81515997072103, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5815218162215614, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.04921300014301559, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059575.1296756}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059575.1296756}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059575.229891, "x": -88.23580199183341, "y": 40.092829274070674, "z": 202.81515997072103, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5797428162215614, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.04613718763407712, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059575.2297137}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.45, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059575.2297137}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059575.330043, "x": -88.23580199183341, "y": 40.092829274070674, "z": 202.81515997072103, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5779818162215618, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.04306137512513865, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059575.3297334}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.42, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059575.3297334}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059575.4298313, "x": -88.23580199183341, "y": 40.092829274070674, "z": 202.81515997072103, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5768178162215616, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.041010833452512996, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059575.4297}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059575.4297}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059575.529828, "x": -88.23580199183341, "y": 40.092829274070674, "z": 202.81515997072103, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5745138162215615, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.0369097501072617, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059575.5296986}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059575.5296986}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059575.62984, "x": -88.23580085286297, "y": 40.09282742056813, "z": 202.79545337495512, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5739428162215616, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.03588447927094887, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059575.6297054}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.35, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059575.6297054}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059575.7298071, "x": -88.23580085286297, "y": 40.09282742056813, "z": 202.79545337495512, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.571678816221562, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.03178339592569757, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059575.7296944}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059575.7296944}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059575.829791, "x": -88.23580085286297, "y": 40.09282742056813, "z": 202.79545337495512, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.571678816221562, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.03178339592569757, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059575.829606}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059575.829606}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059575.9300172, "x": -88.23580085286297, "y": 40.09282742056813, "z": 202.79545337495512, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5694468162215616, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.027682312580446275, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059575.9297147}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.27, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059575.9297147}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059576.0298116, "x": -88.23580085286297, "y": 40.09282742056813, "z": 202.79545337495512, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5688938162215615, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.026657041744133452, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059576.0296948}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.26, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059576.0296948}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059576.1298041, "x": -88.23580000636406, "y": 40.092826291260245, "z": 202.7621487067726, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5672468162215614, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.023581229235194977, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059576.1296906}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059576.1296906}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059576.2298365, "x": -88.23580000636406, "y": 40.092826291260245, "z": 202.7621487067726, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5667018162215616, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.02255595839888215, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059576.2296708}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059576.2296708}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059576.3298569, "x": -88.23580000636406, "y": 40.092826291260245, "z": 202.7621487067726, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5661588162215616, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.021530687562569324, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059576.3297045}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.21, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059576.3297045}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059576.4297702, "x": -88.23580000636406, "y": 40.092826291260245, "z": 202.7621487067726, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5650788162215616, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.019480145889943675, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059576.429675}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.19, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059576.429675}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059576.529877, "x": -88.23580000636406, "y": 40.092826291260245, "z": 202.7621487067726, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5640068162215615, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.017429604217318026, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059576.5297024}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.17, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059576.5297024}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059576.6297767, "x": -88.23579939782209, "y": 40.09282562286814, "z": 202.7169530229106, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5634738162215616, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.0164043333810052, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059576.6296635}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059576.6296635}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059576.7299418, "x": -88.23579939782209, "y": 40.09282562286814, "z": 202.7169530229106, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5624138162215617, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.014353791708379552, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059576.7296755}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.14, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059576.7296755}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059576.829862, "x": -88.23579939782209, "y": 40.09282562286814, "z": 202.7169530229106, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5613618162215617, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.012303250035753898, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059576.829712}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059576.829712}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059576.9298742, "x": -88.23579939782209, "y": 40.09282562286814, "z": 202.7169530229106, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5608388162215614, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.011277979199441075, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059576.9296918}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.11, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059576.9296918}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059577.030071, "x": -88.23579939782209, "y": 40.09282562286814, "z": 202.7169530229106, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5603178162215614, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.010252708363128249, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059577.0297554}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059577.0297554}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059577.1299706, "x": -88.23579901813305, "y": 40.092825210254524, "z": 202.72233793121117, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.559281816221562, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.0082021666905026, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059577.1297052}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059577.1297052}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059577.2297857, "x": -88.23579901813305, "y": 40.092825210254524, "z": 202.72233793121117, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5587668162215618, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.007176895854189776, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059577.2296612}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059577.2296612}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059577.3298147, "x": -88.23579901813305, "y": 40.092825210254524, "z": 202.72233793121117, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5582538162215616, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.006151625017876949, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059577.329694}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059577.329694}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059577.4297888, "x": -88.23579901813305, "y": 40.092825210254524, "z": 202.72233793121117, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5577428162215616, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.0051263541815641245, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059577.429663}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059577.429663}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059577.529878, "x": -88.23579901813305, "y": 40.092825210254524, "z": 202.72233793121117, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5572338162215615, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.0041010833452513, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059577.5297065}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.04, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059577.5297065}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059577.6300478, "x": -88.2357985884493, "y": 40.09282499070913, "z": 202.72639531703993, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5567268162215617, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.0030758125089384745, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059577.629711}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059577.629711}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059577.7298434, "x": -88.2357985884493, "y": 40.09282499070913, "z": 202.72639531703993, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5562218162215617, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.00205054167262565, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059577.7297118}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059577.7297118}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059577.8298016, "x": -88.2357985884493, "y": 40.09282499070913, "z": 202.72639531703993, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5557188162215616, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.001025270836312825, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059577.8296828}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059577.8296828}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059577.9298096, "x": -88.2357985884493, "y": 40.09282499070913, "z": 202.72639531703993, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059577.9296947}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059577.9296947}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059578.0298274, "x": -88.2357985884493, "y": 40.09282499070913, "z": 202.72639531703993, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059578.0297065}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059578.0297065}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059578.129788, "x": -88.23579844955927, "y": 40.0928249037585, "z": 202.72405532436608, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059578.129689}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059578.129689}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059578.2298002, "x": -88.23579844955927, "y": 40.0928249037585, "z": 202.72405532436608, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059578.2296922}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059578.2296922}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059578.3299682, "x": -88.23579844955927, "y": 40.0928249037585, "z": 202.72405532436608, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059578.3297346}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059578.3297346}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059578.4298298, "x": -88.23579844955927, "y": 40.0928249037585, "z": 202.72405532436608, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059578.4296753}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059578.4296753}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059578.5299382, "x": -88.23579844955927, "y": 40.0928249037585, "z": 202.72405532436608, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059578.529725}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059578.529725}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059578.6302674, "x": -88.23579838482311, "y": 40.09282505287427, "z": 202.71185512928065, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059578.629704}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059578.629704}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059578.7299507, "x": -88.23579838482311, "y": 40.09282505287427, "z": 202.71185512928065, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059578.7297277}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059578.7297277}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059578.8298583, "x": -88.23579838482311, "y": 40.09282505287427, "z": 202.71185512928065, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059578.8297012}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059578.8297012}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059578.9298286, "x": -88.23579838482311, "y": 40.09282505287427, "z": 202.71185512928065, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059578.9296963}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059578.9296963}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059579.0299635, "x": -88.23579838482311, "y": 40.09282505287427, "z": 202.71185512928065, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059579.029749}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059579.029749}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059579.1298895, "x": -88.23579838195434, "y": 40.09282511619641, "z": 202.70803979707125, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059579.1297224}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059579.1297224}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059579.2298322, "x": -88.23579838195434, "y": 40.09282511619641, "z": 202.70803979707125, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059579.2297015}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059579.2297015}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059579.329939, "x": -88.23579838195434, "y": 40.09282511619641, "z": 202.70803979707125, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059579.329703}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059579.329703}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059579.4298081, "x": -88.23579838195434, "y": 40.09282511619641, "z": 202.70803979707125, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059579.4296937}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059579.4296937}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059579.529925, "x": -88.23579838195434, "y": 40.09282511619641, "z": 202.70803979707125, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059579.529714}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059579.529714}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059579.6301272, "x": -88.23579831118995, "y": 40.09282506940683, "z": 202.70306176099703, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -5.18, "front_wheel_angle": -0.2566796411682128, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059579.6297424}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059579.6297424}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059579.7298117, "x": -88.23579831118995, "y": 40.09282506940683, "z": 202.70306176099703, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -5.152, "front_wheel_angle": -0.2551739367916594, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059579.7296915}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059579.7296915}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059579.8298275, "x": -88.23579831118995, "y": 40.09282506940683, "z": 202.70306176099703, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -5.125, "front_wheel_angle": -0.2537234397081409, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059579.829693}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.125, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059579.829693}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059579.929846, "x": -88.23579831118995, "y": 40.09282506940683, "z": 202.70306176099703, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5572338162215615, "steering_wheel_angle": -5.124, "front_wheel_angle": -0.2536697445429914, "heading_rate": -0.004050853362105684, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059579.9297087}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.04, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.124, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059579.9297087}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059580.0298138, "x": -88.23579831118995, "y": 40.09282506940683, "z": 202.70306176099703, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5572338162215615, "steering_wheel_angle": -5.1, "front_wheel_angle": -0.2523816369846099, "heading_rate": -0.004029381066569398, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059580.0296683}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.04, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.1, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059580.0296683}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059580.129815, "x": -88.23579823011998, "y": 40.09282505210231, "z": 202.69470927775276, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5567268162215617, "steering_wheel_angle": -5.1, "front_wheel_angle": -0.2523816369846099, "heading_rate": -0.0030220357999270484, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059580.1296673}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.1, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059580.1296673}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059580.2298083, "x": -88.23579823011998, "y": 40.09282505210231, "z": 202.69470927775276, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5572338162215615, "steering_wheel_angle": -5.028, "front_wheel_angle": -0.24852393153393051, "heading_rate": -0.003965159454305766, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059580.2296932}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.04, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.028, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059580.2296932}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059580.3298373, "x": -88.23579823011998, "y": 40.09282505210231, "z": 202.69470927775276, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5562218162215617, "steering_wheel_angle": -4.941, "front_wheel_angle": -0.24387569451779262, "heading_rate": -0.001943972019001505, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059580.3296704}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.941, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059580.3296704}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059580.4298558, "x": -88.23579823011998, "y": 40.09282505210231, "z": 202.69470927775276, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5567268162215617, "steering_wheel_angle": -4.862, "front_wheel_angle": -0.23966724999623354, "heading_rate": -0.0028636412608464583, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059580.4296982}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.862, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059580.4296982}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059580.5297668, "x": -88.23579823011998, "y": 40.09282505210231, "z": 202.69470927775276, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5557188162215616, "steering_wheel_angle": -4.7, "front_wheel_angle": -0.2310736749372902, "heading_rate": -0.0009190475965322966, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059580.5296586}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.7, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059580.5296586}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059580.6299582, "x": -88.23579805955178, "y": 40.09282500083405, "z": 202.68593316593677, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5613618162215617, "steering_wheel_angle": -4.408, "front_wheel_angle": -0.2157053484550111, "heading_rate": -0.010270983375630326, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059580.629729}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059580.629729}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059580.7298398, "x": -88.23579805955178, "y": 40.09282500083405, "z": 202.68593316593677, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5645418162215616, "steering_wheel_angle": -4.114, "front_wheel_angle": -0.2003854416911835, "heading_rate": -0.014281266578770093, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059580.7296956}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.114, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059580.7296956}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059580.8297806, "x": -88.23579805955178, "y": 40.09282500083405, "z": 202.68593316593677, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5745138162215615, "steering_wheel_angle": -3.89, "front_wheel_angle": -0.18881384100989393, "heading_rate": -0.026872043365439933, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059580.8296616}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.89, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059580.8296616}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059580.929873, "x": -88.23579805955178, "y": 40.09282500083405, "z": 202.68593316593677, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5739428162215616, "steering_wheel_angle": -3.645, "front_wheel_angle": -0.17625463966684932, "heading_rate": -0.024349987567475508, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059580.929671}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.35, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.645, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059580.929671}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059581.0297673, "x": -88.23579805955178, "y": 40.09282500083405, "z": 202.68593316593677, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5900618162215614, "steering_wheel_angle": -3.309, "front_wheel_angle": -0.15919151783060803, "heading_rate": -0.03888321064118782, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059581.0296588}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.309, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059581.0296588}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059581.1297562, "x": -88.23579898416871, "y": 40.092826178909874, "z": 202.66363926724858, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5976938162215615, "steering_wheel_angle": -2.897, "front_wheel_angle": -0.13851499998537747, "heading_rate": -0.04029754410716953, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059581.129656}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.897, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059581.129656}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059581.2298222, "x": -88.23579898416871, "y": 40.092826178909874, "z": 202.66363926724858, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6117428162215615, "steering_wheel_angle": -2.274, "front_wheel_angle": -0.10774277041308192, "heading_rate": -0.040138103491612405, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059581.229698}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.274, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059581.229698}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059581.3298473, "x": -88.23579898416871, "y": 40.092826178909874, "z": 202.66363926724858, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6303588162215616, "steering_wheel_angle": -1.608, "front_wheel_angle": -0.07547077213305324, "heading_rate": -0.03573961359780844, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059581.3296957}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.21, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.608, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059581.3296957}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059581.4299777, "x": -88.23579898416871, "y": 40.092826178909874, "z": 202.66363926724858, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6371178162215614, "steering_wheel_angle": -0.937, "front_wheel_angle": -0.04357252471184328, "heading_rate": -0.02214068632242321, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059581.429687}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.937, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059581.429687}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059581.5299344, "x": -88.23579898416871, "y": 40.092826178909874, "z": 202.66363926724858, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6666068162215617, "steering_wheel_angle": -0.295, "front_wheel_angle": -0.01360040549396957, "heading_rate": -0.008872686591527606, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059581.5296988}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.295, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059581.5296988}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059581.6298103, "x": -88.23580300680317, "y": 40.09283043931438, "z": 202.68768653068034, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6784788162215616, "steering_wheel_angle": 0.139, "front_wheel_angle": 0.006395132496591273, "heading_rate": 0.004521620164466564, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059581.6296663}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.139, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059581.6296663}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059581.7299428, "x": -88.23580300680317, "y": 40.09283043931438, "z": 202.68768653068034, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6988338162215615, "steering_wheel_angle": 0.676, "front_wheel_angle": 0.031324652516870874, "heading_rate": 0.024970000145192593, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059581.729698}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.04, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059581.729698}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059581.8297627, "x": -88.23580300680317, "y": 40.09283043931438, "z": 202.68768653068034, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.717393816221562, "steering_wheel_angle": 1.043, "front_wheel_angle": 0.04857188712145214, "heading_rate": 0.04253385551743841, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059581.829657}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.043, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059581.829657}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059581.9297874, "x": -88.23580300680317, "y": 40.09283043931438, "z": 202.68768653068034, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7397268162215616, "steering_wheel_angle": 1.34, "front_wheel_angle": 0.0626582881989223, "heading_rate": 0.06053469947314177, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059581.9296894}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.47, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.34, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059581.9296894}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059582.029798, "x": -88.23580300680317, "y": 40.09283043931438, "z": 202.68768653068034, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7672938162215615, "steering_wheel_angle": 1.769, "front_wheel_angle": 0.08321509447500476, "heading_rate": 0.08927231387349364, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059582.029686}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.769, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059582.029686}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059582.1298106, "x": -88.23581093818028, "y": 40.09283809331668, "z": 202.6989660791307, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7864818162215617, "steering_wheel_angle": 2.26, "front_wheel_angle": 0.10705786915591158, "heading_rate": 0.12258155847661217, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059582.129693}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.26, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059582.129693}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059582.2297952, "x": -88.23581093818028, "y": 40.09283809331668, "z": 202.6989660791307, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.822193816221562, "steering_wheel_angle": 2.761, "front_wheel_angle": 0.1317476308725911, "heading_rate": 0.16771458523790855, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059582.2296827}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.761, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059582.2296827}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059582.32993, "x": -88.23581093818028, "y": 40.09283809331668, "z": 202.6989660791307, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8361138162215616, "steering_wheel_angle": 3.19, "front_wheel_angle": 0.1531919702998037, "heading_rate": 0.20265221258398097, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059582.3296833}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.19, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059582.3296833}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059582.4298182, "x": -88.23581093818028, "y": 40.09283809331668, "z": 202.6989660791307, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8734068162215616, "steering_wheel_angle": 3.447, "front_wheel_angle": 0.16617738160476903, "heading_rate": 0.2404482611212906, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059582.4296741}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.447, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059582.4296741}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059582.529946, "x": -88.23581093818028, "y": 40.09283809331668, "z": 202.6989660791307, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8419988162215617, "steering_wheel_angle": 3.572, "front_wheel_angle": 0.17253180906157306, "heading_rate": 0.2321255899315817, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059582.5297182}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.572, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059582.5297182}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059582.6297884, "x": -88.23582383121918, "y": 40.09284839160452, "z": 202.6924856735111, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.934942816221562, "steering_wheel_angle": 3.651, "front_wheel_angle": 0.1765610167453426, "heading_rate": 0.28923372964306315, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059582.6296601}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.651, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059582.6296601}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059582.7298462, "x": -88.23582383121918, "y": 40.09284839160452, "z": 202.6924856735111, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8946738162215615, "steering_wheel_angle": 3.707, "front_wheel_angle": 0.17942341273343, "heading_rate": 0.2720608675778984, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059582.7296915}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.84, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.707, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059582.7296915}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059582.8298404, "x": -88.23582383121918, "y": 40.09284839160452, "z": 202.6924856735111, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8921418162215615, "steering_wheel_angle": 3.828, "front_wheel_angle": 0.18562608284343493, "heading_rate": 0.2802147957959035, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059582.8296907}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.828, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059582.8296907}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059582.9298828, "x": -88.23582383121918, "y": 40.09284839160452, "z": 202.6924856735111, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9524018162215615, "steering_wheel_angle": 4.005, "front_wheel_angle": 0.19474388432783063, "heading_rate": 0.329766832258553, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059582.9296741}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.005, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059582.9296741}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059583.029928, "x": -88.23582383121918, "y": 40.09284839160452, "z": 202.6924856735111, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8997618162215613, "steering_wheel_angle": 4.22, "front_wheel_angle": 0.20589145752080373, "heading_rate": 0.31653977557820373, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059583.0297186}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.88, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.22, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059583.0297186}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059583.1298902, "x": -88.23584078096053, "y": 40.09285865649622, "z": 202.70519508835122, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9443018162215617, "steering_wheel_angle": 4.481, "front_wheel_angle": 0.21953299036417562, "heading_rate": 0.3678143921556144, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059583.1297097}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.481, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059583.1297097}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059583.229816, "x": -88.23584078096053, "y": 40.09285865649622, "z": 202.70519508835122, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9296388162215616, "steering_wheel_angle": 4.743, "front_wheel_angle": 0.23334994790976307, "heading_rate": 0.38158741417919195, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059583.2296686}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.11, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.743, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059583.2296686}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059583.3298714, "x": -88.23584078096053, "y": 40.09285865649622, "z": 202.70519508835122, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9126218162215616, "steering_wheel_angle": 4.952, "front_wheel_angle": 0.24446261166732686, "heading_rate": 0.3878195424606083, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059583.329675}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.952, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059583.329675}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059583.430063, "x": -88.23584078096053, "y": 40.09285865649622, "z": 202.70519508835122, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9100338162215618, "steering_wheel_angle": 5.144, "front_wheel_angle": 0.2547440134782493, "heading_rate": 0.40280842913515524, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059583.4297073}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.96, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.144, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059583.4297073}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059583.529821, "x": -88.23584078096053, "y": 40.09285865649622, "z": 202.70519508835122, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9035988162215616, "steering_wheel_angle": 5.352, "front_wheel_angle": 0.26596241616836896, "heading_rate": 0.41607306036607306, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059583.529664}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.352, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059583.529664}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059583.629764, "x": -88.23586021776603, "y": 40.09286633774787, "z": 202.71265163466668, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9230538162215614, "steering_wheel_angle": 5.549, "front_wheel_angle": 0.2766661406021191, "heading_rate": 0.45032416432802275, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059583.6296554}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.549, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059583.6296554}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059583.7298427, "x": -88.23586021776603, "y": 40.09286633774787, "z": 202.71265163466668, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9309618162215614, "steering_wheel_angle": 5.695, "front_wheel_angle": 0.2846491913148338, "heading_rate": 0.47089463042116403, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059583.7296667}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.695, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059583.7296667}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059583.829814, "x": -88.23586021776603, "y": 40.09286633774787, "z": 202.71265163466668, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9113268162215618, "steering_wheel_angle": 5.844, "front_wheel_angle": 0.292841277096359, "heading_rate": 0.4675756112735878, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059583.8296623}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.844, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059583.8296623}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059583.9298759, "x": -88.23586021776603, "y": 40.09286633774787, "z": 202.71265163466668, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8972138162215613, "steering_wheel_angle": 6.008, "front_wheel_angle": 0.3019115357330952, "heading_rate": 0.469580971839891, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059583.929674}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.86, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.008, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059583.929674}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059584.029827, "x": -88.23586021776603, "y": 40.09286633774787, "z": 202.71265163466668, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.887101816221562, "steering_wheel_angle": 6.126, "front_wheel_angle": 0.3084729287341699, "heading_rate": 0.4704986131395315, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059584.029665}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.78, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.126, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059584.029665}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059584.1299596, "x": -88.23588085030323, "y": 40.09287081010682, "z": 202.69745699525765, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8997618162215613, "steering_wheel_angle": 6.198, "front_wheel_angle": 0.31249117215030564, "heading_rate": 0.48966281279079804, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059584.1296828}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.88, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.198, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059584.1296828}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059584.2297993, "x": -88.23588085030323, "y": 40.09287081010682, "z": 202.69745699525765, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9256818162215614, "steering_wheel_angle": 6.282, "front_wheel_angle": 0.31719333594720883, "heading_rate": 0.5231921104007047, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059584.2296867}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.282, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059584.2296867}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059584.3298328, "x": -88.23588085030323, "y": 40.09287081010682, "z": 202.69745699525765, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8771178162215616, "steering_wheel_angle": 6.396, "front_wheel_angle": 0.3235995854707914, "heading_rate": 0.48474203213723926, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059584.329692}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.7, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.396, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059584.329692}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059584.4297469, "x": -88.23588085030323, "y": 40.09287081010682, "z": 202.69745699525765, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8384618162215616, "steering_wheel_angle": 6.505, "front_wheel_angle": 0.32975182545215126, "heading_rate": 0.45187378423335894, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059584.4296522}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.505, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059584.4296522}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059584.5298474, "x": -88.23588085030323, "y": 40.09287081010682, "z": 202.69745699525765, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8934068162215616, "steering_wheel_angle": 6.611, "front_wheel_angle": 0.3357603523321452, "heading_rate": 0.5220975792646826, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059584.5296934}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.611, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059584.5296934}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059584.6298242, "x": -88.23590099109768, "y": 40.09287148699839, "z": 202.70409042912235, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9100338162215618, "steering_wheel_angle": 6.754, "front_wheel_angle": 0.34390679189946705, "heading_rate": 0.5539956955382042, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059584.6296875}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.96, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.754, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059584.6296875}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059584.7299197, "x": -88.23590099109768, "y": 40.09287148699839, "z": 202.70409042912235, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8515188162215614, "steering_wheel_angle": 6.911, "front_wheel_angle": 0.35290537281094514, "heading_rate": 0.5021298864086505, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059584.729715}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.49, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.911, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059584.729715}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059584.8298085, "x": -88.23590099109768, "y": 40.09287148699839, "z": 202.70409042912235, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8419988162215617, "steering_wheel_angle": 7.036, "front_wheel_angle": 0.36011141634712235, "heading_rate": 0.50154980474334, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059584.8296788}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.036, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059584.8296788}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059584.9302204, "x": -88.23590099109768, "y": 40.09287148699839, "z": 202.70409042912235, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8771178162215616, "steering_wheel_angle": 7.167, "front_wheel_angle": 0.3677035765566131, "heading_rate": 0.5567685069890258, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059584.9297264}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.7, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.167, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059584.9297264}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059585.0297415, "x": -88.23590099109768, "y": 40.09287148699839, "z": 202.70409042912235, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8997618162215613, "steering_wheel_angle": 7.339, "front_wheel_angle": 0.3777355505105144, "heading_rate": 0.601383921251718, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059585.0296512}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.88, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.339, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059585.0296512}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059585.1298163, "x": -88.23591970290556, "y": 40.09286824450506, "z": 202.6748848207095, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8503218162215616, "steering_wheel_angle": 7.488, "front_wheel_angle": 0.38648557298892333, "heading_rate": 0.5532011612647078, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059585.1296852}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.488, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059585.1296852}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059585.2299032, "x": -88.23591970290556, "y": 40.09286824450506, "z": 202.6748848207095, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8503218162215616, "steering_wheel_angle": 7.644, "front_wheel_angle": 0.395707115896075, "heading_rate": 0.5678681681890992, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059585.229673}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.644, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059585.229673}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059585.3298013, "x": -88.23591970290556, "y": 40.09286824450506, "z": 202.6748848207095, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8934068162215616, "steering_wheel_angle": 7.874, "front_wheel_angle": 0.4094184234964523, "heading_rate": 0.6492148327932973, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059585.329686}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.874, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059585.329686}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059585.4298632, "x": -88.23591970290556, "y": 40.09286824450506, "z": 202.6748848207095, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8384618162215616, "steering_wheel_angle": 8.091, "front_wheel_angle": 0.42248428466901883, "heading_rate": 0.5935538517763319, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059585.4296765}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.091, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059585.4296765}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059585.5299478, "x": -88.23591970290556, "y": 40.09286824450506, "z": 202.6748848207095, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8845938162215616, "steering_wheel_angle": 8.251, "front_wheel_angle": 0.4322008831062699, "heading_rate": 0.6775160468580713, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059585.5296788}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.76, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.251, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059585.5296788}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059585.6298294, "x": -88.23593573855706, "y": 40.092861678542185, "z": 202.64364117286587, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8491268162215615, "steering_wheel_angle": 8.345, "front_wheel_angle": 0.4379428640766379, "heading_rate": 0.6347251989035231, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059585.6296883}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.47, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.345, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059585.6296883}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059585.7298, "x": -88.23593573855706, "y": 40.092861678542185, "z": 202.64364117286587, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8796018162215615, "steering_wheel_angle": 8.424, "front_wheel_angle": 0.4427880328744324, "heading_rate": 0.6890587519698664, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059585.729682}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.424, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059585.729682}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059585.8297858, "x": -88.23593573855706, "y": 40.092861678542185, "z": 202.64364117286587, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8539188162215616, "steering_wheel_angle": 8.525, "front_wheel_angle": 0.4490087105978664, "heading_rate": 0.6606382852166698, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059585.829679}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.51, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.525, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059585.829679}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059585.9298444, "x": -88.23593573855706, "y": 40.092861678542185, "z": 202.64364117286587, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.887101816221562, "steering_wheel_angle": 8.571, "front_wheel_angle": 0.451851747829665, "heading_rate": 0.7166362489666289, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059585.9296582}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.78, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.571, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059585.9296582}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059586.0297995, "x": -88.23593573855706, "y": 40.092861678542185, "z": 202.64364117286587, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8599538162215614, "steering_wheel_angle": 8.633, "front_wheel_angle": 0.45569352579212036, "heading_rate": 0.6815405474855745, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059586.0296578}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.633, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059586.0296578}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059586.129744, "x": -88.23594830015116, "y": 40.092851852433775, "z": 202.65362736961643, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8820938162215617, "steering_wheel_angle": 8.701, "front_wheel_angle": 0.4599202132427073, "heading_rate": 0.7236745156345288, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059586.1296499}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.701, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059586.1296499}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059586.2299943, "x": -88.23594830015116, "y": 40.092851852433775, "z": 202.65362736961643, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8734068162215616, "steering_wheel_angle": 8.765, "front_wheel_angle": 0.46391093188242316, "heading_rate": 0.7172688096931571, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059586.229694}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.765, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059586.229694}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059586.329856, "x": -88.23594830015116, "y": 40.092851852433775, "z": 202.65362736961643, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8883588162215617, "steering_wheel_angle": 8.839, "front_wheel_angle": 0.4685406566913075, "heading_rate": 0.7493116604855996, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059586.3296998}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.79, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.839, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059586.3296998}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059586.4297793, "x": -88.23594830015116, "y": 40.092851852433775, "z": 202.65362736961643, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8858468162215614, "steering_wheel_angle": 8.856, "front_wheel_angle": 0.4696066012660974, "heading_rate": 0.7473304706802817, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059586.4296556}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.856, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059586.4296556}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059586.5299149, "x": -88.23594830015116, "y": 40.092851852433775, "z": 202.65362736961643, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8921418162215615, "steering_wheel_angle": 8.856, "front_wheel_angle": 0.4696066012660974, "heading_rate": 0.7572420153842642, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059586.5296688}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.856, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059586.5296688}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059586.6297598, "x": -88.23595709185525, "y": 40.09283953192101, "z": 202.57967533572398, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8972138162215613, "steering_wheel_angle": 8.858, "front_wheel_angle": 0.4697320647225748, "heading_rate": 0.765409159411275, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059586.6296532}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.86, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.858, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059586.6296532}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059586.7297788, "x": -88.23595709185525, "y": 40.09283953192101, "z": 202.57967533572398, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8984868162215616, "steering_wheel_angle": 8.865, "front_wheel_angle": 0.4701712834529436, "heading_rate": 0.7682273439907649, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059586.729654}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.865, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059586.729654}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059586.8297722, "x": -88.23595709185525, "y": 40.09283953192101, "z": 202.57967533572398, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9074538162215617, "steering_wheel_angle": 8.879, "front_wheel_angle": 0.47105017237401464, "heading_rate": 0.7838256784233361, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059586.829676}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.94, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.879, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059586.829676}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059586.929776, "x": -88.23595709185525, "y": 40.09283953192101, "z": 202.57967533572398, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9074538162215617, "steering_wheel_angle": 8.897, "front_wheel_angle": 0.4721810586001065, "heading_rate": 0.7860188887702196, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059586.92968}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.94, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.897, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059586.92968}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059587.0299828, "x": -88.23595709185525, "y": 40.09283953192101, "z": 202.57967533572398, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9100338162215618, "steering_wheel_angle": 8.905, "front_wheel_angle": 0.47268399533984073, "heading_rate": 0.7909899834178523, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059587.0297563}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.96, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.905, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059587.0297563}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059587.1298823, "x": -88.2359610782288, "y": 40.09282526454578, "z": 202.48668575457773, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9139188162215617, "steering_wheel_angle": 8.905, "front_wheel_angle": 0.47268399533984073, "heading_rate": 0.7969823317770784, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059587.1296957}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.905, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059587.1296957}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059587.229771, "x": -88.2359610782288, "y": 40.09282526454578, "z": 202.48668575457773, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9269988162215617, "steering_wheel_angle": 8.904, "front_wheel_angle": 0.47262111744338703, "heading_rate": 0.8168301059726555, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059587.2296538}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.09, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.904, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059587.2296538}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059587.3302937, "x": -88.2359610782288, "y": 40.09282526454578, "z": 202.48668575457773, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9126218162215616, "steering_wheel_angle": 8.895, "front_wheel_angle": 0.47205535527007203, "heading_rate": 0.7937523890168703, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059587.3297255}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.895, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059587.3297255}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059587.429786, "x": -88.2359610782288, "y": 40.09282526454578, "z": 202.48668575457773, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9402788162215616, "steering_wheel_angle": 8.879, "front_wheel_angle": 0.47105017237401464, "heading_rate": 0.8335608103029895, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059587.429676}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.19, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.879, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059587.429676}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059587.5298471, "x": -88.2359610782288, "y": 40.09282526454578, "z": 202.48668575457773, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9269988162215617, "steering_wheel_angle": 8.863, "front_wheel_angle": 0.4700457770433493, "heading_rate": 0.8116468997087921, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059587.5296917}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.09, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.863, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059587.5296917}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059587.6298068, "x": -88.23595907277047, "y": 40.09281035268282, "z": 202.40504442769162, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9336138162215617, "steering_wheel_angle": 8.855, "front_wheel_angle": 0.4695438741371666, "heading_rate": 0.8205483400982699, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059587.629684}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.14, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.855, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059587.629684}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059587.729747, "x": -88.23595907277047, "y": 40.09281035268282, "z": 202.40504442769162, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9296388162215616, "steering_wheel_angle": 8.852, "front_wheel_angle": 0.4693557111422108, "heading_rate": 0.8142225120127778, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059587.729649}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.11, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.852, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059587.729649}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059587.8298874, "x": -88.23595907277047, "y": 40.09281035268282, "z": 202.40504442769162, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9256818162215614, "steering_wheel_angle": 8.835, "front_wheel_angle": 0.46828997473867956, "heading_rate": 0.8061450470626088, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059587.8296852}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.835, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059587.8296852}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059587.929891, "x": -88.23595907277047, "y": 40.09281035268282, "z": 202.40504442769162, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.932286816221562, "steering_wheel_angle": 8.768, "front_wheel_angle": 0.464098299995615, "heading_rate": 0.8075496940805112, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059587.9297013}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.768, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059587.9297013}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059588.0298584, "x": -88.23595907277047, "y": 40.09281035268282, "z": 202.40504442769162, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9074538162215617, "steering_wheel_angle": 8.701, "front_wheel_angle": 0.4599202132427073, "heading_rate": 0.7623736875935944, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059588.02967}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.94, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.701, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059588.02967}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059588.1298952, "x": -88.23595051472702, "y": 40.092796449162684, "z": 202.35024149531728, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9243668162215615, "steering_wheel_angle": 8.643, "front_wheel_angle": 0.4563142333969362, "heading_rate": 0.7804012057476792, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059588.1296763}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.643, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059588.1296763}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059588.2297847, "x": -88.23595051472702, "y": 40.092796449162684, "z": 202.35024149531728, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9389418162215613, "steering_wheel_angle": 8.633, "front_wheel_angle": 0.45569352579212036, "heading_rate": 0.8002358113735116, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059588.229682}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.633, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059588.229682}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059588.3297603, "x": -88.23595051472702, "y": 40.092796449162684, "z": 202.35024149531728, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9087428162215616, "steering_wheel_angle": 8.61, "front_wheel_angle": 0.45426702413281483, "heading_rate": 0.753475875270342, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059588.3296568}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.61, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059588.3296568}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059588.429783, "x": -88.23595051472702, "y": 40.092796449162684, "z": 202.35024149531728, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9336138162215617, "steering_wheel_angle": 8.574, "front_wheel_angle": 0.4520373791152698, "heading_rate": 0.7852582683191615, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059588.4296532}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.14, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.574, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059588.4296532}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059588.5297956, "x": -88.23595051472702, "y": 40.092796449162684, "z": 202.35024149531728, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9061668162215617, "steering_wheel_angle": 8.548, "front_wheel_angle": 0.4504294535355341, "heading_rate": 0.7423782875619453, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059588.529683}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.548, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059588.529683}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059588.6298606, "x": -88.23593652904817, "y": 40.09278501451796, "z": 202.3623847412988, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9336138162215617, "steering_wheel_angle": 8.546, "front_wheel_angle": 0.4503058491593953, "heading_rate": 0.7818007341762304, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059588.6296837}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.14, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.546, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059588.6296837}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059588.730068, "x": -88.23593652904817, "y": 40.09278501451796, "z": 202.3623847412988, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9165188162215614, "steering_wheel_angle": 8.542, "front_wheel_angle": 0.4500586755851637, "heading_rate": 0.756773833327809, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059588.7297184}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.542, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059588.7297184}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059588.829793, "x": -88.23593652904817, "y": 40.09278501451796, "z": 202.3623847412988, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9230538162215614, "steering_wheel_angle": 8.502, "front_wheel_angle": 0.44758951395131896, "heading_rate": 0.7613856981863649, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059588.8296592}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.502, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059588.8296592}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059588.9297807, "x": -88.23593652904817, "y": 40.09278501451796, "z": 202.3623847412988, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9139188162215617, "steering_wheel_angle": 8.435, "front_wheel_angle": 0.4434640984974334, "heading_rate": 0.7403621410074401, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059588.9296727}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.435, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059588.9296727}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059589.0297868, "x": -88.23593652904817, "y": 40.09278501451796, "z": 202.3623847412988, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9178218162215614, "steering_wheel_angle": 8.368, "front_wheel_angle": 0.43935163876699146, "heading_rate": 0.7380291438697083, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059589.0296545}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.368, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059589.0296545}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059589.1297922, "x": -88.23591889083322, "y": 40.09277731928056, "z": 202.3641860731426, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.919126816221562, "steering_wheel_angle": 8.322, "front_wheel_angle": 0.43653559696935723, "heading_rate": 0.7344598937428801, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059589.1296554}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.322, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059589.1296554}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059589.229764, "x": -88.23591889083322, "y": 40.09277731928056, "z": 202.3641860731426, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9178218162215614, "steering_wheel_angle": 8.308, "front_wheel_angle": 0.43567973565969137, "heading_rate": 0.7310015488220972, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059589.2296486}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.308, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059589.2296486}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059589.3297157, "x": -88.23591889083322, "y": 40.09277731928056, "z": 202.3641860731426, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9178218162215614, "steering_wheel_angle": 8.305, "front_wheel_angle": 0.435496409142308, "heading_rate": 0.7306513144155176, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059589.3296106}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059589.3296106}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059589.4298, "x": -88.23591889083322, "y": 40.09277731928056, "z": 202.3641860731426, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9126218162215616, "steering_wheel_angle": 8.27, "front_wheel_angle": 0.43335948160671606, "heading_rate": 0.7193436538806096, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059589.4296784}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.27, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059589.4296784}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059589.529821, "x": -88.23591889083322, "y": 40.09277731928056, "z": 202.3641860731426, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.919126816221562, "steering_wheel_angle": 8.196, "front_wheel_angle": 0.42885276004154593, "heading_rate": 0.7197850929542842, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059589.5296612}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.196, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059589.5296612}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059589.629912, "x": -88.23589889862717, "y": 40.092774135197686, "z": 202.37768818541304, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9126218162215616, "steering_wheel_angle": 8.027, "front_wheel_angle": 0.4186174564768732, "heading_rate": 0.6917042684238968, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059589.629704}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.027, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059589.629704}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059589.7299728, "x": -88.23589889862717, "y": 40.092774135197686, "z": 202.37768818541304, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9178218162215614, "steering_wheel_angle": 7.763, "front_wheel_angle": 0.4027838432535989, "heading_rate": 0.6690764898570399, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059589.7297208}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.763, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059589.7297208}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059589.8297932, "x": -88.23589889862717, "y": 40.092774135197686, "z": 202.37768818541304, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9113268162215618, "steering_wheel_angle": 7.484, "front_wheel_angle": 0.3862499413077201, "heading_rate": 0.6306685396367768, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059589.8296797}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.484, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059589.8296797}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059589.92976, "x": -88.23589889862717, "y": 40.092774135197686, "z": 202.37768818541304, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9100338162215618, "steering_wheel_angle": 7.245, "front_wheel_angle": 0.3722439277594726, "heading_rate": 0.6039725702712211, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059589.9296508}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.96, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.245, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059589.9296508}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059590.0297587, "x": -88.23589889862717, "y": 40.092774135197686, "z": 202.37768818541304, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9100338162215618, "steering_wheel_angle": 6.99, "front_wheel_angle": 0.3574552652680887, "heading_rate": 0.5777583617091213, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059590.029652}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.96, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.99, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059590.029652}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059590.129847, "x": -88.2358784452111, "y": 40.09277542582584, "z": 202.3692935246768, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9126218162215616, "steering_wheel_angle": 6.679, "front_wheel_angle": 0.3396283283515335, "heading_rate": 0.5493002505966501, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059590.1297107}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.679, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059590.1297107}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059590.22995, "x": -88.2358784452111, "y": 40.09277542582584, "z": 202.3692935246768, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9061668162215617, "steering_wheel_angle": 6.304, "front_wheel_angle": 0.3184274019814137, "heading_rate": 0.5060566032159632, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059590.229716}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.304, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059590.229716}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059590.3300672, "x": -88.2358784452111, "y": 40.09277542582584, "z": 202.3692935246768, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9100338162215618, "steering_wheel_angle": 5.887, "front_wheel_angle": 0.29521399596454595, "heading_rate": 0.4704046724333422, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059590.32971}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.96, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.887, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059590.32971}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059590.4299355, "x": -88.2358784452111, "y": 40.09277542582584, "z": 202.3692935246768, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9048818162215615, "steering_wheel_angle": 5.406, "front_wheel_angle": 0.2688887516966327, "heading_rate": 0.4219545249882063, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059590.4296732}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.406, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059590.4296732}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059590.5297868, "x": -88.2358784452111, "y": 40.09277542582584, "z": 202.3692935246768, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9061668162215617, "steering_wheel_angle": 4.892, "front_wheel_angle": 0.24126401371389364, "heading_rate": 0.377735678490221, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059590.5296571}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.892, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059590.5296571}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059590.6297824, "x": -88.23585827931755, "y": 40.092779844836016, "z": 202.32670979663206, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9113268162215618, "steering_wheel_angle": 4.421, "front_wheel_angle": 0.21638628552779446, "heading_rate": 0.3409052153937809, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059590.6296806}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.421, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059590.6296806}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059590.7297802, "x": -88.23585827931755, "y": 40.092779844836016, "z": 202.32670979663206, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9061668162215617, "steering_wheel_angle": 3.971, "front_wheel_angle": 0.19298830702281455, "heading_rate": 0.3000009467544161, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059590.729683}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.971, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059590.729683}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059590.8297987, "x": -88.23585827931755, "y": 40.092779844836016, "z": 202.32670979663206, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9178218162215614, "steering_wheel_angle": 3.543, "front_wheel_angle": 0.17105530790786522, "heading_rate": 0.2712611565725747, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059590.829681}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.543, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059590.829681}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059590.9298928, "x": -88.23585827931755, "y": 40.092779844836016, "z": 202.32670979663206, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9204338162215615, "steering_wheel_angle": 3.137, "front_wheel_angle": 0.15052713280604746, "heading_rate": 0.23936121704541696, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059590.9296918}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.04, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.137, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059590.9296918}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059591.0298045, "x": -88.23585827931755, "y": 40.092779844836016, "z": 202.32670979663206, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9429588162215614, "steering_wheel_angle": 2.637, "front_wheel_angle": 0.12560190908633634, "heading_rate": 0.20764936238207024, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059591.0296736}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.21, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.637, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059591.0296736}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059591.1298294, "x": -88.23583780821113, "y": 40.09278639445259, "z": 202.34830291072873, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9416178162215614, "steering_wheel_angle": 1.989, "front_wheel_angle": 0.09385584324251976, "heading_rate": 0.15443598071381154, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059591.1296985}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.989, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059591.1296985}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059591.229818, "x": -88.23583780821113, "y": 40.09278639445259, "z": 202.34830291072873, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9660618162215617, "steering_wheel_angle": 1.268, "front_wheel_angle": 0.05923264523385525, "heading_rate": 0.10146204178835258, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059591.2296581}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.268, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059591.2296581}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059591.3300457, "x": -88.23583780821113, "y": 40.09278639445259, "z": 202.34830291072873, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9996618162215616, "steering_wheel_angle": 0.683, "front_wheel_angle": 0.031652002199527254, "heading_rate": 0.05714105623539867, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059591.3297355}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.683, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059591.3297355}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059591.4297612, "x": -88.23583780821113, "y": 40.09278639445259, "z": 202.34830291072873, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": 0.241, "front_wheel_angle": 0.011102899666132838, "heading_rate": 0.019864597705977812, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059591.4296486}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.241, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059591.4296486}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059591.5300071, "x": -88.23583780821113, "y": 40.09278639445259, "z": 202.34830291072873, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.038838816221562, "steering_wheel_angle": -0.098, "front_wheel_angle": -0.004506366295246533, "heading_rate": -0.008607922011724984, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059591.5297182}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.098, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059591.5297182}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059591.6297693, "x": -88.23581490647217, "y": 40.09279477003603, "z": 202.35530146768824, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": -0.358, "front_wheel_angle": -0.016518702304634907, "heading_rate": -0.03220149322507243, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059591.6296504}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.358, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059591.6296504}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059591.7297657, "x": -88.23581490647217, "y": 40.09279477003603, "z": 202.35530146768824, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": -0.541, "front_wheel_angle": -0.02502361077791638, "heading_rate": -0.050350977043393266, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059591.7296493}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.541, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059591.7296493}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059591.8297634, "x": -88.23581490647217, "y": 40.09279477003603, "z": 202.35530146768824, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": -0.646, "front_wheel_angle": -0.02992242970913208, "heading_rate": -0.06313646940971518, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059591.8296473}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.646, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059591.8296473}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059591.9298167, "x": -88.23581490647217, "y": 40.09279477003603, "z": 202.35530146768824, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.142353816221561, "steering_wheel_angle": -0.706, "front_wheel_angle": -0.0327280183149596, "heading_rate": -0.07110655455057327, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059591.929681}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.706, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059591.929681}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059592.029796, "x": -88.23581490647217, "y": 40.09279477003603, "z": 202.35530146768824, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": -0.778, "front_wheel_angle": -0.036100776407875464, "heading_rate": -0.08069773220437994, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059592.0296533}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.778, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059592.0296533}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059592.129831, "x": -88.23581490647217, "y": 40.09279477003603, "z": 202.35530146768824, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1966388162215615, "steering_wheel_angle": -0.86, "front_wheel_angle": -0.03995006119136725, "heading_rate": -0.09196528268887337, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059592.1296618}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.86, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059592.1296618}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059592.229735, "x": -88.23578691720819, "y": 40.0928045765365, "z": 202.35488014776186, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.223742816221561, "steering_wheel_angle": -0.874, "front_wheel_angle": -0.04060812093150487, "heading_rate": -0.09602119687334071, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059592.2296438}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.874, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059592.2296438}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059592.3298714, "x": -88.23578691720819, "y": 40.0928045765365, "z": 202.35488014776186, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.2531018162215615, "steering_wheel_angle": -0.923, "front_wheel_angle": -0.04291332422162926, "heading_rate": -0.10433001840859797, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059592.3296938}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.923, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059592.3296938}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059592.4298177, "x": -88.23578691720819, "y": 40.0928045765365, "z": 202.35488014776186, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.267117816221561, "steering_wheel_angle": -0.963, "front_wheel_angle": -0.04479742910803116, "heading_rate": -0.11031747846394079, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059592.4296973}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.963, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059592.4296973}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059592.529765, "x": -88.23578691720819, "y": 40.0928045765365, "z": 202.35488014776186, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": -1.001, "front_wheel_angle": -0.04658925565539817, "heading_rate": -0.11765020936815362, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059592.5296743}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.001, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059592.5296743}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059592.6298683, "x": -88.2357535109948, "y": 40.09281482485894, "z": 202.37375739824486, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.324461816221562, "steering_wheel_angle": -1.07, "front_wheel_angle": -0.04984765468737686, "heading_rate": -0.12900979127086595, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059592.6296744}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.07, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059592.6296744}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059592.7297845, "x": -88.2357535109948, "y": 40.09281482485894, "z": 202.37375739824486, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.340958816221562, "steering_wheel_angle": -1.177, "front_wheel_angle": -0.05491290011400435, "heading_rate": -0.14407670598117314, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059592.7296624}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.177, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059592.7296624}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059592.8300521, "x": -88.2357535109948, "y": 40.09281482485894, "z": 202.37375739824486, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": -1.309, "front_wheel_angle": -0.06118250825951029, "heading_rate": -0.16439417351502753, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059592.8297138}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.309, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059592.8297138}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059592.9303, "x": -88.2357535109948, "y": 40.09281482485894, "z": 202.37375739824486, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": -1.356, "front_wheel_angle": -0.06342048542414276, "heading_rate": -0.1724079211124898, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059592.9297342}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.356, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059592.9297342}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059593.029782, "x": -88.2357535109948, "y": 40.09281482485894, "z": 202.37375739824486, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.400926816221562, "steering_wheel_angle": -1.287, "front_wheel_angle": -0.060135961059043876, "heading_rate": -0.16533834109269008, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059593.029684}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.287, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059593.029684}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059593.1297746, "x": -88.23571560281178, "y": 40.092824066412575, "z": 202.3550174070214, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": -1.193, "front_wheel_angle": -0.055671619167927885, "heading_rate": -0.15499685266281263, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059593.1296742}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.193, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059593.1296742}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059593.2297308, "x": -88.23571560281178, "y": 40.092824066412575, "z": 202.3550174070214, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.449201816221562, "steering_wheel_angle": -1.132, "front_wheel_angle": -0.05278081801907127, "heading_rate": -0.15023498610513966, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059593.2296424}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.132, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059593.2296424}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059593.3297882, "x": -88.23571560281178, "y": 40.092824066412575, "z": 202.3550174070214, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.449201816221562, "steering_wheel_angle": -1.122, "front_wheel_angle": -0.052307384988657446, "heading_rate": -0.1488849370014363, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059593.3296814}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.122, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059593.3296814}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059593.4297917, "x": -88.23571560281178, "y": 40.092824066412575, "z": 202.3550174070214, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.464913816221562, "steering_wheel_angle": -1.063, "front_wheel_angle": -0.04951680838841576, "heading_rate": -0.14247729052504346, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059593.4296768}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.063, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059593.4296768}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059593.5299737, "x": -88.23571560281178, "y": 40.092824066412575, "z": 202.3550174070214, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.480753816221561, "steering_wheel_angle": -1.063, "front_wheel_angle": -0.04951680838841576, "heading_rate": -0.14402595672640262, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059593.529697}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.973, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059593.529697}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059593.6297405, "x": -88.23567414441538, "y": 40.092831554393925, "z": 202.3529105844101, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.496721816221561, "steering_wheel_angle": -0.82, "front_wheel_angle": -0.0380712819240583, "heading_rate": -0.1118884537572188, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059593.6296422}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.82, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059593.6296422}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059593.729817, "x": -88.23567414441538, "y": 40.092831554393925, "z": 202.3529105844101, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.514838816221562, "steering_wheel_angle": -0.82, "front_wheel_angle": -0.0380712819240583, "heading_rate": -0.11322754429420681, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059593.7296824}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.82, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059593.7296824}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059593.8297555, "x": -88.23567414441538, "y": 40.092831554393925, "z": 202.3529105844101, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.531078816221561, "steering_wheel_angle": -0.639, "front_wheel_angle": -0.029595408552037412, "heading_rate": -0.08892779784012099, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059593.8296456}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.639, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059593.8296456}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059593.929801, "x": -88.23567414441538, "y": 40.092831554393925, "z": 202.3529105844101, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.547446816221561, "steering_wheel_angle": -0.48, "front_wheel_angle": -0.022183997714701854, "heading_rate": -0.06734294683218864, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059593.9296784}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.48, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059593.9296784}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059594.0297499, "x": -88.23567414441538, "y": 40.092831554393925, "z": 202.3529105844101, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.563942816221561, "steering_wheel_angle": -0.063, "front_wheel_angle": -0.002895617708822582, "heading_rate": -0.008879165056046228, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059594.0296457}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.063, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059594.0296457}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059594.1298862, "x": -88.23563015363942, "y": 40.09283765836979, "z": 202.36708187512787, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.580566816221562, "steering_wheel_angle": -0.063, "front_wheel_angle": -0.002895617708822582, "heading_rate": -0.008969653362349886, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059594.1297245}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.063, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059594.1297245}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059594.2298536, "x": -88.23563015363942, "y": 40.09283765836979, "z": 202.36708187512787, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": 0.315, "front_wheel_angle": 0.01452631818334394, "heading_rate": 0.045511432410709735, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059594.2296684}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.315, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059594.2296684}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059594.3297803, "x": -88.23563015363942, "y": 40.09283765836979, "z": 202.36708187512787, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": 0.315, "front_wheel_angle": 0.01452631818334394, "heading_rate": 0.04596541178637766, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059594.3296502}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.315, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059594.3296502}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059594.4298015, "x": -88.23563015363942, "y": 40.09283765836979, "z": 202.36708187512787, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": 0.364, "front_wheel_angle": 0.016796891165313556, "heading_rate": 0.053151412181124895, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059594.4296882}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.364, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059594.4296882}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059594.5300174, "x": -88.23563015363942, "y": 40.09283765836979, "z": 202.36708187512787, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.633341816221561, "steering_wheel_angle": 0.205, "front_wheel_angle": 0.00943988328959379, "heading_rate": 0.0301642730726026, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059594.529739}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.205, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059594.529739}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059594.6298609, "x": -88.23558430827806, "y": 40.09284419798547, "z": 202.34574800728225, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.650493816221561, "steering_wheel_angle": 0.205, "front_wheel_angle": 0.00943988328959379, "heading_rate": 0.030459278188227076, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059594.6296542}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.26, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.205, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059594.6296542}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059594.7297878, "x": -88.23558430827806, "y": 40.09284419798547, "z": 202.34574800728225, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.667773816221562, "steering_wheel_angle": 0.152, "front_wheel_angle": 0.00699443621917048, "heading_rate": 0.02278693334164431, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059594.7296777}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059594.7296777}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059594.8298953, "x": -88.23558430827806, "y": 40.09284419798547, "z": 202.34574800728225, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.650493816221561, "steering_wheel_angle": 0.121, "front_wheel_angle": 0.005565666667536317, "heading_rate": 0.017958156785174158, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059594.8296883}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.26, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.121, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059594.8296883}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059594.9300015, "x": -88.23558430827806, "y": 40.09284419798547, "z": 202.34574800728225, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.687366816221561, "steering_wheel_angle": 0.118, "front_wheel_angle": 0.005427460639263251, "heading_rate": 0.017872633770644516, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059594.9296823}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.118, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059594.9296823}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059595.029789, "x": -88.23558430827806, "y": 40.09284419798547, "z": 202.34574800728225, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.650493816221561, "steering_wheel_angle": 0.13, "front_wheel_angle": 0.005980350353755554, "heading_rate": 0.01929620422911777, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059595.0296466}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.26, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.13, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059595.0296466}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059595.1300242, "x": -88.23553699635626, "y": 40.09285146422524, "z": 202.3728990177724, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.667773816221562, "steering_wheel_angle": 0.102, "front_wheel_angle": 0.0046905463413625375, "heading_rate": 0.015281032570029687, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059595.1296837}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.102, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059595.1296837}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059595.2297506, "x": -88.23553699635626, "y": 40.09285146422524, "z": 202.3728990177724, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.667773816221562, "steering_wheel_angle": 0.04, "front_wheel_angle": 0.0018379325036962971, "heading_rate": 0.005987646226781056, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059595.2296488}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.04, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059595.2296488}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059595.3297546, "x": -88.23553699635626, "y": 40.09285146422524, "z": 202.3728990177724, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.650493816221561, "steering_wheel_angle": -0.003, "front_wheel_angle": -0.00013777808953256048, "heading_rate": -0.0004445496198203346, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059595.3296454}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.26, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.003, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059595.3296454}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059595.4297366, "x": -88.23553699635626, "y": 40.09285146422524, "z": 202.3728990177724, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": -0.043, "front_wheel_angle": -0.0019758552115223572, "heading_rate": -0.006251737515811949, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059595.4296408}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.043, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059595.4296408}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059595.530449, "x": -88.23553699635626, "y": 40.09285146422524, "z": 202.3728990177724, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.687366816221561, "steering_wheel_angle": -0.088, "front_wheel_angle": -0.004046001037507012, "heading_rate": -0.013323427681113683, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059595.5297084}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.088, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059595.5297084}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059595.6297843, "x": -88.23548954269032, "y": 40.09285878441329, "z": 202.36061203361544, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.650493816221561, "steering_wheel_angle": -0.116, "front_wheel_angle": -0.005335329359043072, "heading_rate": -0.017214936980650512, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059595.62966}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.26, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.116, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059595.62966}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059595.7297482, "x": -88.23548954269032, "y": 40.09285878441329, "z": 202.36061203361544, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": -0.118, "front_wheel_angle": -0.005427460639263251, "heading_rate": -0.01717299330275452, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059595.7296433}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.118, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059595.7296433}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059595.830097, "x": -88.23548954269032, "y": 40.09285878441329, "z": 202.36061203361544, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.580566816221562, "steering_wheel_angle": -0.114, "front_wheel_angle": -0.005243202935496302, "heading_rate": -0.016241789178731737, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059595.8296695}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.114, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059595.8296695}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059595.930223, "x": -88.23548954269032, "y": 40.09285878441329, "z": 202.36061203361544, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": -0.137, "front_wheel_angle": -0.00630295017488376, "heading_rate": -0.0199431923840215, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059595.9296763}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.137, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059595.9296763}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059596.0297828, "x": -88.23548954269032, "y": 40.09285878441329, "z": 202.36061203361544, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.563942816221561, "steering_wheel_angle": -0.214, "front_wheel_angle": -0.009855488640690276, "heading_rate": -0.03022191046228591, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059596.029652}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.214, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059596.029652}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059596.1297333, "x": -88.23544343063101, "y": 40.09286594693463, "z": 202.3916469584737, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.580566816221562, "steering_wheel_angle": -0.331, "front_wheel_angle": -0.015267403553108584, "heading_rate": -0.04729684295864147, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059596.1296394}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.331, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059596.1296394}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059596.2297382, "x": -88.23544343063101, "y": 40.09286594693463, "z": 202.3916469584737, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.531078816221561, "steering_wheel_angle": -0.492, "front_wheel_angle": -0.02274224190601014, "heading_rate": -0.06832734285847526, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059596.2296405}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.492, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059596.2296405}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059596.3297675, "x": -88.23544343063101, "y": 40.09286594693463, "z": 202.3916469584737, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.531078816221561, "steering_wheel_angle": -0.636, "front_wheel_angle": -0.029455275622164906, "heading_rate": -0.08850648448410821, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059596.329644}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059596.329644}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059596.4298365, "x": -88.23544343063101, "y": 40.09286594693463, "z": 202.3916469584737, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.464913816221562, "steering_wheel_angle": -0.703, "front_wheel_angle": -0.03258763022088541, "heading_rate": -0.09372261559176602, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059596.4296546}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.703, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059596.4296546}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059596.529735, "x": -88.23544343063101, "y": 40.09286594693463, "z": 202.3916469584737, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.449201816221562, "steering_wheel_angle": -0.759, "front_wheel_angle": -0.03521009983017194, "heading_rate": -0.10017012015366936, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059596.5296397}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.759, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059596.5296397}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059596.6297603, "x": -88.23539932437686, "y": 40.09287146970621, "z": 202.37729960992513, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": -0.927, "front_wheel_angle": -0.0431016412863275, "heading_rate": -0.11708673646177316, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059596.62966}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.927, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059596.62966}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059596.7298713, "x": -88.23539932437686, "y": 40.09287146970621, "z": 202.37729960992513, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": -1.237, "front_wheel_angle": -0.05775984750252602, "heading_rate": -0.1569835760348615, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059596.7296553}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.237, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059596.7296553}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059596.8303132, "x": -88.23539932437686, "y": 40.09287146970621, "z": 202.37729960992513, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.324461816221562, "steering_wheel_angle": -1.605, "front_wheel_angle": -0.07532680726257195, "heading_rate": -0.19515967567986187, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059596.8297424}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.605, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059596.8297424}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059596.9297562, "x": -88.23539932437686, "y": 40.09287146970621, "z": 202.37729960992513, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3099338162215615, "steering_wheel_angle": -1.96, "front_wheel_angle": -0.0924492973790707, "heading_rate": -0.23685423686090104, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059596.929645}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.54, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.96, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059596.929645}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059597.0297318, "x": -88.23539932437686, "y": 40.09287146970621, "z": 202.37729960992513, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.267117816221561, "steering_wheel_angle": -2.25, "front_wheel_angle": -0.10656882841119421, "heading_rate": -0.26325657573547007, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059597.029638}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.25, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059597.029638}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059597.1299856, "x": -88.23535928588153, "y": 40.09287434718195, "z": 202.36074327790928, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.223742816221561, "steering_wheel_angle": -2.413, "front_wheel_angle": -0.11455839424398295, "heading_rate": -0.2719242913972049, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059597.1298103}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.413, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059597.1298103}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059597.2297802, "x": -88.23535928588153, "y": 40.09287434718195, "z": 202.36074327790928, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.210126816221561, "steering_wheel_angle": -2.547, "front_wheel_angle": -0.12115580076401539, "heading_rate": -0.283929717260332, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059597.2296424}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.547, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059597.2296424}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059597.3303933, "x": -88.23535928588153, "y": 40.09287434718195, "z": 202.36074327790928, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": -2.787, "front_wheel_angle": -0.13303920686785958, "heading_rate": -0.2948435798218515, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059597.329964}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.787, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059597.329964}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059597.4297647, "x": -88.23535928588153, "y": 40.09287434718195, "z": 202.36074327790928, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": -3.156, "front_wheel_angle": -0.1514819420291163, "heading_rate": -0.3363100078366357, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059597.4296458}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.156, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059597.4296458}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059597.5298166, "x": -88.23535928588153, "y": 40.09287434718195, "z": 202.36074327790928, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": -3.513, "front_wheel_angle": -0.16952934172950673, "heading_rate": -0.361066643211345, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059597.5296485}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.513, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059597.5296485}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059597.6302054, "x": -88.23532451809125, "y": 40.09287328012706, "z": 202.40297354901682, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": -3.824, "front_wheel_angle": -0.18542064363285193, "heading_rate": -0.3890721012053757, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059597.6298172}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.824, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059597.6298172}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059597.7303696, "x": -88.23532451809125, "y": 40.09287328012706, "z": 202.40297354901682, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": -3.989, "front_wheel_angle": -0.19391748404874573, "heading_rate": -0.38893495165029934, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059597.7297242}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.989, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059597.7297242}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059597.8298266, "x": -88.23532451809125, "y": 40.09287328012706, "z": 202.40297354901682, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": -4.193, "front_wheel_angle": -0.20448712349034504, "heading_rate": -0.40424033937030335, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059597.8296373}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.193, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059597.8296373}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059597.929838, "x": -88.23532451809125, "y": 40.09287328012706, "z": 202.40297354901682, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": -4.462, "front_wheel_angle": -0.21853583565363527, "heading_rate": -0.42594737698907725, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059597.9297173}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.462, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059597.9297173}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059598.0297348, "x": -88.23532451809125, "y": 40.09287328012706, "z": 202.40297354901682, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": -4.852, "front_wheel_angle": -0.23913536969647434, "heading_rate": -0.45141183840586185, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059598.0296392}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.852, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059598.0296392}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059598.129788, "x": -88.23529547036844, "y": 40.092867542246324, "z": 202.46014560633614, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": -5.255, "front_wheel_angle": -0.2607202628113516, "heading_rate": -0.48564649381732694, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059598.1296418}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.255, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059598.1296418}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059598.2298832, "x": -88.23529547036844, "y": 40.092867542246324, "z": 202.46014560633614, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": -5.614, "front_wheel_angle": -0.2802148944958338, "heading_rate": -0.5058755924519307, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059598.2296638}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.614, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059598.2296638}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059598.329934, "x": -88.23529547036844, "y": 40.092867542246324, "z": 202.46014560633614, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": -5.961, "front_wheel_angle": -0.29930634685301477, "heading_rate": -0.5315710373085335, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059598.3297431}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.961, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059598.3297431}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059598.4298618, "x": -88.23529547036844, "y": 40.092867542246324, "z": 202.46014560633614, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9592068162215615, "steering_wheel_angle": -6.243, "front_wheel_angle": -0.3150082762632443, "heading_rate": -0.551159270685447, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059598.4296603}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.243, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059598.4296603}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059598.5297801, "x": -88.23529547036844, "y": 40.092867542246324, "z": 202.46014560633614, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9376068162215616, "steering_wheel_angle": -6.55, "front_wheel_angle": -0.3322995110234196, "heading_rate": -0.5621293481566147, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059598.52967}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.17, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.55, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059598.52967}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059598.629734, "x": -88.23527210027952, "y": 40.09285773162458, "z": 202.52441579718686, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9269988162215617, "steering_wheel_angle": -6.877, "front_wheel_angle": -0.3509517360898244, "heading_rate": -0.5849138091965446, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059598.6296399}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.09, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.877, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059598.6296399}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059598.7299478, "x": -88.23527210027952, "y": 40.09285773162458, "z": 202.52441579718686, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9483428162215617, "steering_wheel_angle": -7.217, "front_wheel_angle": -0.37061234230216683, "heading_rate": -0.6450832465242377, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059598.7296672}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.25, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.217, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059598.7296672}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059598.829796, "x": -88.23527210027952, "y": 40.09285773162458, "z": 202.52441579718686, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9283178162215613, "steering_wheel_angle": -7.43, "front_wheel_angle": -0.38307288048444066, "heading_rate": -0.6453979924862678, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059598.8296583}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.43, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059598.8296583}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059598.9297469, "x": -88.23527210027952, "y": 40.09285773162458, "z": 202.52441579718686, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9126218162215616, "steering_wheel_angle": -7.701, "front_wheel_angle": -0.3990921932493567, "heading_rate": -0.655648328632103, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059598.9296443}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.701, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059598.9296443}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059599.0298357, "x": -88.23527210027952, "y": 40.09285773162458, "z": 202.52441579718686, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.934942816221562, "steering_wheel_angle": -8.025, "front_wheel_angle": -0.41849679863923206, "heading_rate": -0.7210151220422417, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059599.0296483}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059599.0296483}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059599.1299176, "x": -88.23525389982044, "y": 40.09284428697422, "z": 202.51880976317253, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9165188162215614, "steering_wheel_angle": -8.356, "front_wheel_angle": -0.43861643749551765, "heading_rate": -0.7347877305262952, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059599.1296709}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.356, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059599.1296709}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059599.2299154, "x": -88.23525389982044, "y": 40.09284428697422, "z": 202.51880976317253, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9100338162215618, "steering_wheel_angle": -8.642, "front_wheel_angle": -0.456252149266228, "heading_rate": -0.7591901085394694, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059599.22968}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.96, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.642, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059599.22968}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059599.3299773, "x": -88.23525389982044, "y": 40.09284428697422, "z": 202.51880976317253, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9283178162215613, "steering_wheel_angle": -8.845, "front_wheel_angle": -0.46891677138205534, "heading_rate": -0.811357828834079, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059599.3296854}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.845, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059599.3296854}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059599.4297557, "x": -88.23525389982044, "y": 40.09284428697422, "z": 202.51880976317253, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.919126816221562, "steering_wheel_angle": -9.024, "front_wheel_angle": -0.4801886436211674, "heading_rate": -0.8199328442440246, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059599.4296408}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.024, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059599.4296408}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059599.5297637, "x": -88.23525389982044, "y": 40.09284428697422, "z": 202.51880976317253, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9126218162215616, "steering_wheel_angle": -9.154, "front_wheel_angle": -0.4884379013047299, "heading_rate": -0.8261349666491212, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059599.5296464}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.154, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059599.5296464}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059599.6298242, "x": -88.23524213785555, "y": 40.09282770416342, "z": 202.43447231340355, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9243668162215615, "steering_wheel_angle": -9.251, "front_wheel_angle": -0.4946283459126384, "heading_rate": -0.8574790885190476, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059599.6296551}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.251, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059599.6296551}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059599.7297513, "x": -88.23524213785555, "y": 40.09282770416342, "z": 202.43447231340355, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9126218162215616, "steering_wheel_angle": -9.358, "front_wheel_angle": -0.5014924990113082, "heading_rate": -0.8523449885119541, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059599.7296412}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.358, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059599.7296412}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059599.82981, "x": -88.23524213785555, "y": 40.09282770416342, "z": 202.43447231340355, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.919126816221562, "steering_wheel_angle": -9.458, "front_wheel_angle": -0.5079418058377274, "heading_rate": -0.8763040627385372, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059599.829644}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.458, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059599.829644}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059599.9298003, "x": -88.23524213785555, "y": 40.09282770416342, "z": 202.43447231340355, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9178218162215614, "steering_wheel_angle": -9.543, "front_wheel_angle": -0.5134500997574741, "heading_rate": -0.8854946121188183, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059599.9296565}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.543, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059599.9296565}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059600.0297515, "x": -88.23524213785555, "y": 40.09282770416342, "z": 202.43447231340355, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9113268162215618, "steering_wheel_angle": -9.59, "front_wheel_angle": -0.5165063977124696, "heading_rate": -0.8807385644135438, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059600.0296395}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.59, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059600.0296395}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059600.129803, "x": -88.23523835098413, "y": 40.092809735154795, "z": 202.34015918914477, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9100338162215618, "steering_wheel_angle": -9.661, "front_wheel_angle": -0.5211377381388662, "heading_rate": -0.888019999674241, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059600.129653}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.96, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.661, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059600.129653}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059600.2297566, "x": -88.23523835098413, "y": 40.092809735154795, "z": 202.34015918914477, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9010388162215617, "steering_wheel_angle": -9.732, "front_wheel_angle": -0.5257865568295523, "heading_rate": -0.8817399251397869, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059600.2296417}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.732, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059600.2296417}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059600.3302653, "x": -88.23523835098413, "y": 40.092809735154795, "z": 202.34015918914477, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9074538162215617, "steering_wheel_angle": -9.787, "front_wheel_angle": -0.529399894952629, "heading_rate": -0.9005226685216465, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059600.3299768}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.94, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.787, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059600.3299768}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059600.4298637, "x": -88.23523835098413, "y": 40.092809735154795, "z": 202.34015918914477, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9087428162215616, "steering_wheel_angle": -9.811, "front_wheel_angle": -0.5309799726540255, "heading_rate": -0.9060839660570313, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059600.4296834}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.811, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059600.4296834}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059600.5297906, "x": -88.23523835098413, "y": 40.092809735154795, "z": 202.34015918914477, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8997618162215613, "steering_wheel_angle": -9.877, "front_wheel_angle": -0.5353357586350693, "heading_rate": -0.8989279137264551, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059600.5296721}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.88, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.877, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059600.5296721}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059600.6297903, "x": -88.2352430596669, "y": 40.092792120962734, "z": 202.33426340534857, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8921418162215615, "steering_wheel_angle": -9.98, "front_wheel_angle": -0.5421647327312799, "heading_rate": -0.8988579473023743, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059600.6296518}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.98, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059600.6296518}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059600.7299457, "x": -88.2352430596669, "y": 40.092792120962734, "z": 202.33426340534857, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8908788162215617, "steering_wheel_angle": -10.055, "front_wheel_angle": -0.5471616200682252, "heading_rate": -0.906670858221772, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059600.7296736}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.055, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059600.7296736}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059600.8298495, "x": -88.2352430596669, "y": 40.092792120962734, "z": 202.33426340534857, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8946738162215615, "steering_wheel_angle": -10.125, "front_wheel_angle": -0.55184413662912, "heading_rate": -0.9234681482552125, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059600.8296556}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.84, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.125, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059600.8296556}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059600.9299772, "x": -88.2352430596669, "y": 40.092792120962734, "z": 202.33426340534857, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8833428162215613, "steering_wheel_angle": -10.196, "front_wheel_angle": -0.5566122678844252, "heading_rate": -0.9114846473450143, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059600.9296656}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.75, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.196, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059600.9296656}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059601.029795, "x": -88.2352430596669, "y": 40.092792120962734, "z": 202.33426340534857, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8796018162215615, "steering_wheel_angle": -10.321, "front_wheel_angle": -0.565053372207252, "heading_rate": -0.9212981774708343, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059601.029644}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.321, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059601.029644}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059601.1298137, "x": -88.23525486523424, "y": 40.09277719943861, "z": 202.37411264725034, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.887101816221562, "steering_wheel_angle": -10.462, "front_wheel_angle": -0.5746475098830345, "heading_rate": -0.9561407910067784, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059601.1296496}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.78, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.462, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059601.1296496}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059601.2297487, "x": -88.23525486523424, "y": 40.09277719943861, "z": 202.37411264725034, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8820938162215617, "steering_wheel_angle": -10.593, "front_wheel_angle": -0.5836317510458763, "heading_rate": -0.9647615122605353, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059601.2296374}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.593, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059601.2296374}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059601.3298132, "x": -88.23525486523424, "y": 40.09277719943861, "z": 202.37411264725034, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8684868162215613, "steering_wheel_angle": -10.661, "front_wheel_angle": -0.5883226509716466, "heading_rate": -0.9459681537154867, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059601.329646}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.63, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.661, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059601.329646}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059601.4297805, "x": -88.23525486523424, "y": 40.09277719943861, "z": 202.37411264725034, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8684868162215613, "steering_wheel_angle": -10.751, "front_wheel_angle": -0.5945604024524355, "heading_rate": -0.9588032063823526, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059601.4296412}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.63, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.751, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059601.4296412}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059601.5298986, "x": -88.23525486523424, "y": 40.09277719943861, "z": 202.37411264725034, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8623818162215615, "steering_wheel_angle": -10.902, "front_wheel_angle": -0.6051021055885552, "heading_rate": -0.9672338014716064, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059601.5296693}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.902, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059601.5296693}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059601.6299899, "x": -88.23527240642383, "y": 40.09276714890876, "z": 202.33166506008368, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8635988162215615, "steering_wheel_angle": -10.939, "front_wheel_angle": -0.607699972673806, "heading_rate": -0.9753311843141564, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059601.6296992}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.59, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.939, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059601.6296992}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059601.7298448, "x": -88.23527240642383, "y": 40.09276714890876, "z": 202.33166506008368, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.858742816221562, "steering_wheel_angle": -10.938, "front_wheel_angle": -0.6076296825741517, "heading_rate": -0.9643193693823632, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059601.729657}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.55, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.938, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059601.729657}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059601.8297331, "x": -88.23527240642383, "y": 40.09276714890876, "z": 202.33166506008368, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8491268162215615, "steering_wheel_angle": -10.936, "front_wheel_angle": -0.6074891153143884, "heading_rate": -0.9423055837813511, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059601.8296328}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.47, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.936, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059601.8296328}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059601.9297528, "x": -88.23527240642383, "y": 40.09276714890876, "z": 202.33166506008368, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8384618162215616, "steering_wheel_angle": -10.893, "front_wheel_angle": -0.6044710804933966, "heading_rate": -0.9119672145008384, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059601.929638}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.893, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059601.929638}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059602.0297651, "x": -88.23527240642383, "y": 40.09276714890876, "z": 202.33166506008368, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8479338162215617, "steering_wheel_angle": -10.601, "front_wheel_angle": -0.584182644460667, "heading_rate": -0.8936030323491723, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059602.0296667}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.601, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059602.0296667}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059602.1297429, "x": -88.23527240642383, "y": 40.09276714890876, "z": 202.33166506008368, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8783588162215614, "steering_wheel_angle": -10.026, "front_wheel_angle": -0.5452270388324743, "heading_rate": -0.8790340924145018, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059602.129638}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.71, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059602.129638}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059602.2298126, "x": -88.23529270813694, "y": 40.09276294187507, "z": 202.3486556272817, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8176178162215617, "steering_wheel_angle": -9.404, "front_wheel_angle": -0.5044550425166299, "heading_rate": -0.6901265940751121, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059602.2296379}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.404, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059602.2296379}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059602.3298824, "x": -88.23529270813694, "y": 40.09276294187507, "z": 202.3486556272817, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8758788162215616, "steering_wheel_angle": -8.647, "front_wheel_angle": -0.4565625996513026, "heading_rate": -0.7079825040641297, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059602.3296812}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.647, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059602.3296812}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059602.4299219, "x": -88.23529270813694, "y": 40.09276294187507, "z": 202.3486556272817, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8268018162215616, "steering_wheel_angle": -7.81, "front_wheel_angle": -0.4055890921021259, "heading_rate": -0.5501649803528811, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059602.4296849}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.81, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059602.4296849}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059602.5298116, "x": -88.23529270813694, "y": 40.09276294187507, "z": 202.3486556272817, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8896178162215618, "steering_wheel_angle": -7.077, "front_wheel_angle": -0.36248313189893044, "heading_rate": -0.5629350421757032, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059602.5296783}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.8, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.077, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059602.5296783}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059602.6298864, "x": -88.23531343197106, "y": 40.09276316512408, "z": 202.36345197022482, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8575338162215616, "steering_wheel_angle": -6.436, "front_wheel_angle": -0.3258542076417959, "heading_rate": -0.4672512641664698, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059602.629712}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.54, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.436, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059602.629712}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059602.7297761, "x": -88.23531343197106, "y": 40.09276316512408, "z": 202.36345197022482, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.934942816221562, "steering_wheel_angle": -5.829, "front_wheel_angle": -0.29201449104694277, "heading_rate": -0.48731373548421136, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059602.7296665}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.829, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059602.7296665}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059602.829754, "x": -88.23531343197106, "y": 40.09276316512408, "z": 202.36345197022482, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8959428162215617, "steering_wheel_angle": -5.243, "front_wheel_angle": -0.2600730284389915, "heading_rate": -0.4001890616909021, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059602.8296392}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.243, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059602.8296392}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059602.9297607, "x": -88.23531343197106, "y": 40.09276316512408, "z": 202.36345197022482, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9592068162215615, "steering_wheel_angle": -5.022, "front_wheel_angle": -0.2482029024934763, "heading_rate": -0.42865059924540305, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059602.9296396}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.022, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059602.9296396}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059603.0297394, "x": -88.23531343197106, "y": 40.09276316512408, "z": 202.36345197022482, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9799218162215615, "steering_wheel_angle": -5.018, "front_wheel_angle": -0.24798892117689791, "heading_rate": -0.44310143091932963, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059603.0296388}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.018, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059603.0296388}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059603.1298535, "x": -88.23533719689023, "y": 40.09276651788124, "z": 202.35707297899611, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9799218162215615, "steering_wheel_angle": -4.819, "front_wheel_angle": -0.2373814890386437, "heading_rate": -0.4234005122341499, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059603.1296515}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.819, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059603.1296515}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059603.2299256, "x": -88.23533719689023, "y": 40.09276651788124, "z": 202.35707297899611, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": -4.239, "front_wheel_angle": -0.2068804572209981, "heading_rate": -0.4025496836914658, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059603.2296565}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.239, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059603.2296565}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059603.3297896, "x": -88.23533719689023, "y": 40.09276651788124, "z": 202.35707297899611, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": -3.565, "front_wheel_angle": -0.17217528596581325, "heading_rate": -0.34439766391721677, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059603.3296437}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.565, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059603.3296437}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059603.4297254, "x": -88.23533719689023, "y": 40.09276651788124, "z": 202.35707297899611, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": -2.958, "front_wheel_angle": -0.14155959655848158, "heading_rate": -0.2911492264959644, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059603.4296324}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.958, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059603.4296324}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059603.529739, "x": -88.23533719689023, "y": 40.09276651788124, "z": 202.35707297899611, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": -2.307, "front_wheel_angle": -0.1093583097440476, "heading_rate": -0.22774165355316567, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059603.5296342}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059603.5296342}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059603.6297538, "x": -88.23536537854714, "y": 40.092774137835235, "z": 202.3680387884423, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.142353816221561, "steering_wheel_angle": -1.647, "front_wheel_angle": -0.07734344102633908, "heading_rate": -0.16831604253220805, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059603.629637}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.647, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059603.629637}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059603.7299674, "x": -88.23536537854714, "y": 40.092774137835235, "z": 202.3680387884423, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.183278816221561, "steering_wheel_angle": -1.111, "front_wheel_angle": -0.051786760831198334, "heading_rate": -0.11763685304358763, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059603.7296727}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.111, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059603.7296727}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059603.8297784, "x": -88.23536537854714, "y": 40.092774137835235, "z": 202.3680387884423, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1966388162215615, "steering_wheel_angle": -0.733, "front_wheel_angle": -0.033992027103633374, "heading_rate": -0.07823835463949194, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059603.829641}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.733, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059603.829641}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059603.9303286, "x": -88.23536537854714, "y": 40.092774137835235, "z": 202.3680387884423, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.237486816221562, "steering_wheel_angle": -0.508, "front_wheel_angle": -0.023486847789702597, "heading_rate": -0.05625033453870304, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059603.9297626}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.508, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059603.9297626}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059604.0297968, "x": -88.23536537854714, "y": 40.092774137835235, "z": 202.3680387884423, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.237486816221562, "steering_wheel_angle": -0.382, "front_wheel_angle": -0.017631725321869237, "heading_rate": -0.04222409287547642, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059604.0296545}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.382, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059604.0296545}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059604.1298, "x": -88.23539709538927, "y": 40.09278453742424, "z": 202.4070940345322, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": -0.355, "front_wheel_angle": -0.0163796245856467, "heading_rate": -0.040824746698040947, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059604.129668}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.355, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059604.129668}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059604.2297733, "x": -88.23539709538927, "y": 40.09278453742424, "z": 202.4070940345322, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": -0.546, "front_wheel_angle": -0.025256572898768894, "heading_rate": -0.06374693835728279, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059604.229642}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.546, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059604.229642}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059604.3300724, "x": -88.23539709538927, "y": 40.09278453742424, "z": 202.4070940345322, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3099338162215615, "steering_wheel_angle": -0.707, "front_wheel_angle": -0.0327748168923771, "heading_rate": -0.08375940831218072, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059604.3296766}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.54, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.707, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059604.3296766}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059604.4297314, "x": -88.23539709538927, "y": 40.09278453742424, "z": 202.4070940345322, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.355758816221561, "steering_wheel_angle": -0.737, "front_wheel_angle": -0.03417936672177728, "heading_rate": -0.09069074831161755, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059604.4296331}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.737, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059604.4296331}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059604.5300455, "x": -88.23539709538927, "y": 40.09278453742424, "z": 202.4070940345322, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": -0.551, "front_wheel_angle": -0.025489566435968693, "heading_rate": -0.06841845938776367, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059604.529687}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.551, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059604.529687}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059604.6300313, "x": -88.2354321801197, "y": 40.09279634140942, "z": 202.42078334083936, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": -0.168, "front_wheel_angle": -0.0077323233140674475, "heading_rate": -0.02099246799549984, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059604.6297348}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.168, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059604.6297348}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059604.7300084, "x": -88.2354321801197, "y": 40.09279634140942, "z": 202.42078334083936, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.400926816221562, "steering_wheel_angle": 0.32, "front_wheel_angle": 0.01475787342039404, "heading_rate": 0.040529446373690756, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059604.7296786}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.32, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059604.7296786}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059604.8300104, "x": -88.2354321801197, "y": 40.09279634140942, "z": 202.42078334083936, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": 0.751, "front_wheel_angle": 0.034835216246282184, "heading_rate": 0.09801369518824235, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059604.8296928}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.751, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059604.8296928}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059604.9302657, "x": -88.2354321801197, "y": 40.09279634140942, "z": 202.42078334083936, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.449201816221562, "steering_wheel_angle": 1.032, "front_wheel_angle": 0.04805240365351152, "heading_rate": 0.1367542958459783, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059604.929724}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.032, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059604.929724}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059605.0297675, "x": -88.2354321801197, "y": 40.09279634140942, "z": 202.42078334083936, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.464913816221562, "steering_wheel_angle": 1.089, "front_wheel_angle": 0.05074599021193614, "heading_rate": 0.14602008485882587, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059605.029633}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.089, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059605.029633}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059605.129853, "x": -88.23546958235562, "y": 40.09280914231502, "z": 202.44929146349963, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.480753816221561, "steering_wheel_angle": 1.221, "front_wheel_angle": 0.057000194250137144, "heading_rate": 0.16583645555907892, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059605.1296568}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.221, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059605.1296568}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059605.2298195, "x": -88.23546958235562, "y": 40.09280914231502, "z": 202.44929146349963, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.480753816221561, "steering_wheel_angle": 1.514, "front_wheel_angle": 0.07096572857535413, "heading_rate": 0.2065910719831613, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059605.2296584}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.514, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059605.2296584}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059605.3297682, "x": -88.23546958235562, "y": 40.09280914231502, "z": 202.44929146349963, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.496721816221561, "steering_wheel_angle": 1.787, "front_wheel_angle": 0.0840831528106515, "heading_rate": 0.24757799344067472, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059605.3296359}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.787, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059605.3296359}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059605.4297595, "x": -88.23546958235562, "y": 40.09280914231502, "z": 202.44929146349963, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.531078816221561, "steering_wheel_angle": 1.999, "front_wheel_angle": 0.09434113562127162, "heading_rate": 0.28423568389830667, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059605.4296324}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.999, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059605.4296324}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059605.5299711, "x": -88.23546958235562, "y": 40.09280914231502, "z": 202.44929146349963, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.514838816221562, "steering_wheel_angle": 2.154, "front_wheel_angle": 0.10188140720213865, "heading_rate": 0.3039106429372897, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059605.5296662}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.154, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059605.5296662}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059605.6297908, "x": -88.23550989938016, "y": 40.09282018630594, "z": 202.5375094383734, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.563942816221561, "steering_wheel_angle": 2.234, "front_wheel_angle": 0.10578666522146654, "heading_rate": 0.32560037675437997, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059605.6296487}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.234, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059605.6296487}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059605.7298732, "x": -88.23550989938016, "y": 40.09282018630594, "z": 202.5375094383734, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.547446816221561, "steering_wheel_angle": 2.308, "front_wheel_angle": 0.10940729027085981, "heading_rate": 0.33339954280871414, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059605.7296855}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.308, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059605.7296855}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059605.8297691, "x": -88.23550989938016, "y": 40.09282018630594, "z": 202.5375094383734, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.563942816221561, "steering_wheel_angle": 2.367, "front_wheel_angle": 0.11229972954558941, "heading_rate": 0.34581151900214274, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059605.829667}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059605.829667}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059605.929844, "x": -88.23550989938016, "y": 40.09282018630594, "z": 202.5375094383734, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.580566816221562, "steering_wheel_angle": 2.37, "front_wheel_angle": 0.11244693897486696, "heading_rate": 0.34979752417606663, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059605.9296415}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.37, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059605.9296415}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059606.0298, "x": -88.23550989938016, "y": 40.09282018630594, "z": 202.5375094383734, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": 2.392, "front_wheel_angle": 0.11352687867960794, "heading_rate": 0.35719429337105885, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059606.0296814}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.392, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059606.0296814}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059606.1297612, "x": -88.23555356802298, "y": 40.09282676113373, "z": 202.5638964595403, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": 2.392, "front_wheel_angle": 0.11352687867960794, "heading_rate": 0.35719429337105885, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059606.1296463}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.392, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059606.1296463}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059606.229824, "x": -88.23555356802298, "y": 40.09282676113373, "z": 202.5638964595403, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": 2.493, "front_wheel_angle": 0.11849394100934302, "heading_rate": 0.37296652023813237, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059606.2297027}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.493, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059606.2297027}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059606.329935, "x": -88.23555356802298, "y": 40.09282676113373, "z": 202.5638964595403, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": 2.577, "front_wheel_angle": 0.12263648964875909, "heading_rate": 0.38613485666238506, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059606.329686}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.577, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059606.329686}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059606.4298058, "x": -88.23555356802298, "y": 40.09282676113373, "z": 202.5638964595403, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": 2.648, "front_wheel_angle": 0.12614615565488482, "heading_rate": 0.4012650056345447, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059606.4296691}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.648, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059606.4296691}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059606.530204, "x": -88.23555356802298, "y": 40.09282676113373, "z": 202.5638964595403, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": 2.683, "front_wheel_angle": 0.12787906189494458, "heading_rate": 0.4028192964683751, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059606.529805}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.683, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059606.529805}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059606.6298008, "x": -88.23559876328964, "y": 40.09282720837715, "z": 202.598779692821, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": 2.667, "front_wheel_angle": 0.12708664701066283, "heading_rate": 0.4042890005961725, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059606.6296601}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.667, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059606.6296601}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059606.7297292, "x": -88.23559876328964, "y": 40.09282720837715, "z": 202.598779692821, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": 2.6, "front_wheel_angle": 0.12377259580598939, "heading_rate": 0.3936364096040305, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059606.729632}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.6, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059606.729632}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059606.8298469, "x": -88.23559876328964, "y": 40.09282720837715, "z": 202.598779692821, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": 2.501, "front_wheel_angle": 0.11888801699705441, "heading_rate": 0.3779514973955895, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059606.8296616}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.501, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059606.8296616}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059606.9297888, "x": -88.23559876328964, "y": 40.09282720837715, "z": 202.598779692821, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": 2.4, "front_wheel_angle": 0.1139197604439033, "heading_rate": 0.3620166478653686, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059606.929679}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.4, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059606.929679}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059607.0298629, "x": -88.23559876328964, "y": 40.09282720837715, "z": 202.598779692821, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": 2.293, "front_wheel_angle": 0.10867273556698495, "heading_rate": 0.3417978823157373, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059607.029652}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.293, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059607.029652}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059607.1299212, "x": -88.23564358434666, "y": 40.0928211657623, "z": 202.6081392552845, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": 2.224, "front_wheel_angle": 0.10529800177742159, "heading_rate": 0.33440630210225397, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059607.1296763}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.224, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059607.1296763}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059607.229857, "x": -88.23564358434666, "y": 40.0928211657623, "z": 202.6081392552845, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.580566816221562, "steering_wheel_angle": 2.138, "front_wheel_angle": 0.1011014635050197, "heading_rate": 0.3142490100044595, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059607.2296617}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.138, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059607.2296617}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059607.3297586, "x": -88.23564358434666, "y": 40.0928211657623, "z": 202.6081392552845, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": 1.926, "front_wheel_angle": 0.09080175934643682, "heading_rate": 0.28524927419139384, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059607.3296373}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.926, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059607.3296373}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059607.4297402, "x": -88.23564358434666, "y": 40.0928211657623, "z": 202.6081392552845, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.580566816221562, "steering_wheel_angle": 1.609, "front_wheel_angle": 0.07551876316888662, "heading_rate": 0.23437689522608296, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059607.4296358}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.609, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059607.4296358}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059607.5302312, "x": -88.23564358434666, "y": 40.0928211657623, "z": 202.6081392552845, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.547446816221561, "steering_wheel_angle": 1.263, "front_wheel_angle": 0.05899501060280685, "heading_rate": 0.17926709783126235, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059607.5297513}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.263, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059607.5297513}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059607.6297207, "x": -88.23568667694013, "y": 40.09280965751008, "z": 202.56143259921188, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": 0.897, "front_wheel_angle": 0.04168976842853566, "heading_rate": 0.13198550700221545, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059607.6296282}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.897, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059607.6296282}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059607.7297618, "x": -88.23568667694013, "y": 40.09280965751008, "z": 202.56143259921188, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": 0.498, "front_wheel_angle": 0.02302143155467317, "heading_rate": 0.07213457243796385, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059607.7296383}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.498, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059607.7296383}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059607.8297637, "x": -88.23568667694013, "y": 40.09280965751008, "z": 202.56143259921188, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.580566816221562, "steering_wheel_angle": 0.094, "front_wheel_angle": 0.004322205648206082, "heading_rate": 0.013388790714114864, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059607.8296375}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.094, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059607.8296375}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059607.9298472, "x": -88.23568667694013, "y": 40.09280965751008, "z": 202.56143259921188, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.547446816221561, "steering_wheel_angle": -0.295, "front_wheel_angle": -0.01360040549396957, "heading_rate": -0.04128190108752664, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059607.9296482}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.295, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059607.9296482}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059608.0297341, "x": -88.23568667694013, "y": 40.09280965751008, "z": 202.56143259921188, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.531078816221561, "steering_wheel_angle": -0.687, "front_wheel_angle": -0.03183908711445129, "heading_rate": -0.09567396407092538, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059608.029639}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.687, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059608.029639}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059608.1297534, "x": -88.23572924898369, "y": 40.09279622709963, "z": 202.5009658740527, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.580566816221562, "steering_wheel_angle": -1.017, "front_wheel_angle": -0.047344272086904546, "heading_rate": -0.14676595437689974, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059608.1296358}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.017, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059608.1296358}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059608.22973, "x": -88.23572924898369, "y": 40.09279622709963, "z": 202.5009658740527, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.563942816221561, "steering_wheel_angle": -1.238, "front_wheel_angle": -0.05780733713387394, "heading_rate": -0.1774584942543412, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059608.2296293}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.238, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059608.2296293}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059608.32977, "x": -88.23572924898369, "y": 40.09279622709963, "z": 202.5009658740527, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.531078816221561, "steering_wheel_angle": -1.484, "front_wheel_angle": -0.06953048650567983, "heading_rate": -0.20920029716598393, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059608.3296366}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.484, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059608.3296366}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059608.4297643, "x": -88.23572924898369, "y": 40.09279622709963, "z": 202.5009658740527, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.547446816221561, "steering_wheel_angle": -1.809, "front_wheel_angle": -0.08514472655295756, "heading_rate": -0.25905386613353465, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059608.4296381}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.809, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059608.4296381}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059608.529777, "x": -88.23572924898369, "y": 40.09279622709963, "z": 202.5009658740527, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.547446816221561, "steering_wheel_angle": -2.102, "front_wheel_angle": -0.09934793519205654, "heading_rate": -0.30253249511095637, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059608.5295947}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.102, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059608.5295947}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059608.629972, "x": -88.23577308984878, "y": 40.09278532073335, "z": 202.46550005302294, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.531078816221561, "steering_wheel_angle": -2.329, "front_wheel_angle": -0.110436218732018, "heading_rate": -0.333095311052957, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059608.6296518}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.329, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059608.6296518}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059608.7298312, "x": -88.23577308984878, "y": 40.09278532073335, "z": 202.46550005302294, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.531078816221561, "steering_wheel_angle": -2.507, "front_wheel_angle": -0.11918363636593013, "heading_rate": -0.35972133455454636, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059608.7296853}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.507, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059608.7296853}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059608.8297985, "x": -88.23577308984878, "y": 40.09278532073335, "z": 202.46550005302294, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.496721816221561, "steering_wheel_angle": -2.636, "front_wheel_angle": -0.12555244115074954, "heading_rate": -0.3707604968441927, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059608.829649}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059608.829649}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059608.9299917, "x": -88.23577308984878, "y": 40.09278532073335, "z": 202.46550005302294, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.496721816221561, "steering_wheel_angle": -2.68, "front_wheel_angle": -0.12773045467479613, "heading_rate": -0.37726213154903615, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059608.9296694}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.68, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059608.9296694}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059609.0297487, "x": -88.23577308984878, "y": 40.09278532073335, "z": 202.46550005302294, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.514838816221562, "steering_wheel_angle": -2.687, "front_wheel_angle": -0.12807722599678556, "heading_rate": -0.38282511822012044, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059609.0296335}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.687, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059609.0296335}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059609.1297214, "x": -88.23581771120055, "y": 40.09278019484938, "z": 202.49697537122688, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.496721816221561, "steering_wheel_angle": -2.691, "front_wheel_angle": -0.12827541426860797, "heading_rate": -0.3788894686030042, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059609.129627}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.691, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059609.129627}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059609.229767, "x": -88.23581771120055, "y": 40.09278019484938, "z": 202.49697537122688, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.480753816221561, "steering_wheel_angle": -2.686, "front_wheel_angle": -0.12802768270573495, "heading_rate": -0.3741268051118702, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059609.2296364}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.686, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059609.2296364}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059609.329788, "x": -88.23581771120055, "y": 40.09278019484938, "z": 202.49697537122688, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.480753816221561, "steering_wheel_angle": -2.687, "front_wheel_angle": -0.12807722599678556, "heading_rate": -0.3742731773400389, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059609.3296652}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.687, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059609.3296652}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059609.4299543, "x": -88.23581771120055, "y": 40.09278019484938, "z": 202.49697537122688, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.464913816221562, "steering_wheel_angle": -2.663, "front_wheel_angle": -0.1268886036262263, "heading_rate": -0.36677530009187986, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059609.4296737}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.663, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059609.4296737}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059609.529825, "x": -88.23581771120055, "y": 40.09278019484938, "z": 202.49697537122688, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.449201816221562, "steering_wheel_angle": -2.516, "front_wheel_angle": -0.11962716573930246, "heading_rate": -0.34182187573477457, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059609.529669}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.516, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059609.529669}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059609.6298828, "x": -88.23586189885098, "y": 40.092781409006164, "z": 202.49326120989818, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.464913816221562, "steering_wheel_angle": -2.328, "front_wheel_angle": -0.11038720752350173, "heading_rate": -0.3186585949393029, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059609.6296742}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.328, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059609.6296742}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059609.729928, "x": -88.23586189885098, "y": 40.092781409006164, "z": 202.49326120989818, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": -2.203, "front_wheel_angle": -0.10427227998632357, "heading_rate": -0.2943332948415996, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059609.729656}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.203, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059609.729656}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059609.8297887, "x": -88.23586189885098, "y": 40.092781409006164, "z": 202.49326120989818, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": -2.182, "front_wheel_angle": -0.10324719593899165, "heading_rate": -0.2914189824039688, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059609.8296633}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.182, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059609.8296633}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059609.9298086, "x": -88.23586189885098, "y": 40.092781409006164, "z": 202.49326120989818, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": -2.191, "front_wheel_angle": -0.10368643965877679, "heading_rate": -0.29266767548911987, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059609.929677}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.191, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059609.929677}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059610.0298576, "x": -88.23586189885098, "y": 40.092781409006164, "z": 202.49326120989818, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.400926816221562, "steering_wheel_angle": -2.228, "front_wheel_angle": -0.10549344976182612, "heading_rate": -0.29077436737125106, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059610.0296764}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.228, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059610.0296764}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059610.1297472, "x": -88.23590427604744, "y": 40.0927875517223, "z": 202.5024070740769, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": -2.28, "front_wheel_angle": -0.10803638682060206, "heading_rate": -0.2944483888098296, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059610.1296322}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.28, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059610.1296322}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059610.2297275, "x": -88.23590427604744, "y": 40.0927875517223, "z": 202.5024070740769, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.400926816221562, "steering_wheel_angle": -2.267, "front_wheel_angle": -0.1074002841518753, "heading_rate": -0.2960704988220106, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059610.229629}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.267, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059610.229629}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059610.3297718, "x": -88.23590427604744, "y": 40.0927875517223, "z": 202.5024070740769, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": -2.205, "front_wheel_angle": -0.10436994028074537, "heading_rate": -0.2811079724006565, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059610.329638}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.205, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059610.329638}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059610.4298184, "x": -88.23590427604744, "y": 40.0927875517223, "z": 202.5024070740769, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.355758816221561, "steering_wheel_angle": -2.101, "front_wheel_angle": -0.09929925261472419, "heading_rate": -0.2642448383004081, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059610.4296834}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.101, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059610.4296834}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059610.5302095, "x": -88.23590427604744, "y": 40.0927875517223, "z": 202.5024070740769, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.355758816221561, "steering_wheel_angle": -1.984, "front_wheel_angle": -0.09361325027580271, "heading_rate": -0.24902237556210285, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059610.529705}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.984, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059610.529705}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059610.6297634, "x": -88.23594344397338, "y": 40.09279743196305, "z": 202.51410717647502, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.324461816221562, "steering_wheel_angle": -1.83, "front_wheel_angle": -0.08615867764553695, "heading_rate": -0.2233539048475668, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059610.6296537}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.83, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059610.6296537}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059610.7298958, "x": -88.23594344397338, "y": 40.09279743196305, "z": 202.51410717647502, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3099338162215615, "steering_wheel_angle": -1.594, "front_wheel_angle": -0.07479904173387462, "heading_rate": -0.1914453491541048, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059610.7297413}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.54, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.594, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059610.7297413}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059610.8297584, "x": -88.23594344397338, "y": 40.09279743196305, "z": 202.51410717647502, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": -1.298, "front_wheel_angle": -0.060659153759803956, "heading_rate": -0.1513596746182696, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059610.8296647}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.298, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059610.8296647}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059610.9297214, "x": -88.23594344397338, "y": 40.09279743196305, "z": 202.51410717647502, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": -0.993, "front_wheel_angle": -0.046211872687489615, "heading_rate": -0.11525070386673493, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059610.9296255}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.993, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059610.9296255}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059611.0303817, "x": -88.23594344397338, "y": 40.09279743196305, "z": 202.51410717647502, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.237486816221562, "steering_wheel_angle": -0.653, "front_wheel_angle": -0.0302495129438494, "heading_rate": -0.07245550511645268, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059611.0297053}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.653, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059611.0297053}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059611.1297593, "x": -88.23597839458822, "y": 40.092809161695094, "z": 202.55671213917296, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.223742816221561, "steering_wheel_angle": -0.298, "front_wheel_angle": -0.01373926097338927, "heading_rate": -0.03247178107637517, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059611.1296313}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.298, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059611.1296313}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059611.2298677, "x": -88.23597839458822, "y": 40.092809161695094, "z": 202.55671213917296, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.210126816221561, "steering_wheel_angle": 0.009, "front_wheel_angle": 0.00041336676293914716, "heading_rate": 0.0009639842637914325, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059611.2296624}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.009, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059611.2296624}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059611.3298295, "x": -88.23597839458822, "y": 40.092809161695094, "z": 202.55671213917296, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.183278816221561, "steering_wheel_angle": 0.279, "front_wheel_angle": 0.012860030069306591, "heading_rate": 0.029187849168435993, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059611.3296707}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.279, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059611.3296707}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059611.4301116, "x": -88.23597839458822, "y": 40.092809161695094, "z": 202.55671213917296, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": 0.541, "front_wheel_angle": 0.02502361077791638, "heading_rate": 0.05592380362877852, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059611.429691}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.541, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059611.429691}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059611.52977, "x": -88.23597839458822, "y": 40.092809161695094, "z": 202.55671213917296, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.142353816221561, "steering_wheel_angle": 0.837, "front_wheel_angle": 0.038869511495513494, "heading_rate": 0.0844622608547338, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059611.5296612}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.837, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059611.5296612}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059611.629723, "x": -88.23600961962221, "y": 40.09281991900594, "z": 202.55609079001053, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": 1.166, "front_wheel_angle": 0.05439147735423574, "heading_rate": 0.11654671075663323, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059611.629626}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059611.629626}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059611.7297633, "x": -88.23600961962221, "y": 40.09281991900594, "z": 202.55609079001053, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": 1.511, "front_wheel_angle": 0.0708221492626488, "heading_rate": 0.1471467306072329, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059611.7296295}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.511, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059611.7296295}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059611.8297565, "x": -88.23600961962221, "y": 40.09281991900594, "z": 202.55609079001053, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": 1.957, "front_wheel_angle": 0.09230386062830005, "heading_rate": 0.1891112842918673, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059611.8296576}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.957, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059611.8296576}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059611.93021, "x": -88.23600961962221, "y": 40.09281991900594, "z": 202.55609079001053, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": 2.545, "front_wheel_angle": 0.12105713593960765, "heading_rate": 0.24092794551121915, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059611.9296758}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.545, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059611.9296758}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059612.0299218, "x": -88.23600961962221, "y": 40.09281991900594, "z": 202.55609079001053, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": 3.011, "front_wheel_angle": 0.1442095797391043, "heading_rate": 0.27852290775926714, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059612.029673}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.011, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059612.029673}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059612.1298912, "x": -88.23603782839535, "y": 40.092827786890034, "z": 202.5308203891502, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": 3.371, "front_wheel_angle": 0.1623262986864959, "heading_rate": 0.308343015427661, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059612.1296675}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.371, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059612.1296675}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059612.2298508, "x": -88.23603782839535, "y": 40.092827786890034, "z": 202.5308203891502, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": 3.681, "front_wheel_angle": 0.17809379617438537, "heading_rate": 0.3276578623248386, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059612.2296634}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.681, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059612.2296634}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059612.3298378, "x": -88.23603782839535, "y": 40.092827786890034, "z": 202.5308203891502, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": 4.0, "front_wheel_angle": 0.19448558716790762, "heading_rate": 0.35855674674394666, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059612.3296342}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.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": 1744059612.3296342}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059612.4297504, "x": -88.23603782839535, "y": 40.092827786890034, "z": 202.5308203891502, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": 4.356, "front_wheel_angle": 0.2129846110540872, "heading_rate": 0.38015268903616145, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059612.4296558}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.356, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059612.4296558}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059612.529758, "x": -88.23603782839535, "y": 40.092827786890034, "z": 202.5308203891502, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": 4.848, "front_wheel_angle": 0.23892266989375102, "heading_rate": 0.4195962645679443, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059612.5296257}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.848, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059612.5296257}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059612.6297982, "x": -88.2360631788472, "y": 40.09283133541864, "z": 202.5237932333463, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9592068162215615, "steering_wheel_angle": 5.418, "front_wheel_angle": 0.26953983242749463, "heading_rate": 0.46727260083210975, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059612.6296365}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.418, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059612.6296365}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059612.730008, "x": -88.2360631788472, "y": 40.09283133541864, "z": 202.5237932333463, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9483428162215617, "steering_wheel_angle": 5.804, "front_wheel_angle": 0.2906375530822084, "heading_rate": 0.4965647640220687, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059612.7296758}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.25, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.804, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059612.7296758}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059612.8299923, "x": -88.2360631788472, "y": 40.09283133541864, "z": 202.5237932333463, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": 6.185, "front_wheel_angle": 0.3117648271869615, "heading_rate": 0.5551682219278194, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059612.8296804}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.185, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059612.8296804}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059612.929996, "x": -88.2360631788472, "y": 40.09283133541864, "z": 202.5237932333463, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9483428162215617, "steering_wheel_angle": 6.544, "front_wheel_angle": 0.3319595557056009, "heading_rate": 0.5722820866849118, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059612.9296653}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.25, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.544, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059612.9296653}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059613.0297477, "x": -88.2360631788472, "y": 40.09283133541864, "z": 202.5237932333463, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.919126816221562, "steering_wheel_angle": 6.86, "front_wheel_angle": 0.3499759378713981, "heading_rate": 0.5745917749444158, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059613.0296295}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.86, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059613.0296295}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059613.1297524, "x": -88.23608552944044, "y": 40.092830028578845, "z": 202.53677233995734, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9152178162215616, "steering_wheel_angle": 7.151, "front_wheel_angle": 0.36677406061132073, "heading_rate": 0.600244599822722, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059613.1296513}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.151, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059613.1296513}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059613.229781, "x": -88.23608552944044, "y": 40.092830028578845, "z": 202.53677233995734, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9402788162215616, "steering_wheel_angle": 7.37, "front_wheel_angle": 0.37955143242356043, "heading_rate": 0.6528751397128636, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059613.2296576}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.19, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.37, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059613.2296576}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059613.329873, "x": -88.23608552944044, "y": 40.092830028578845, "z": 202.53677233995734, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.934942816221562, "steering_wheel_angle": 7.513, "front_wheel_angle": 0.38795919254215694, "heading_rate": 0.6624944523266157, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059613.3296423}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.513, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059613.3296423}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059613.4297895, "x": -88.23608552944044, "y": 40.092830028578845, "z": 202.53677233995734, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9152178162215616, "steering_wheel_angle": 7.75, "front_wheel_angle": 0.40200895176955476, "heading_rate": 0.6643176486686935, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059613.4296298}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.75, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059613.4296298}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059613.530183, "x": -88.23608552944044, "y": 40.092830028578845, "z": 202.53677233995734, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9023178162215615, "steering_wheel_angle": 8.064, "front_wheel_angle": 0.42085159772430036, "heading_rate": 0.6818820396164597, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059613.5297737}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.9, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.064, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059613.5297737}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059613.6298087, "x": -88.23610474868231, "y": 40.0928242612778, "z": 202.53360372446207, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.919126816221562, "steering_wheel_angle": 8.445, "front_wheel_angle": 0.444079006632352, "heading_rate": 0.7489710873187074, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059613.6296597}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.445, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059613.6296597}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059613.7299764, "x": -88.23610474868231, "y": 40.0928242612778, "z": 202.53360372446207, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.919126816221562, "steering_wheel_angle": 8.802, "front_wheel_angle": 0.46622371207276053, "heading_rate": 0.7921851112351609, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059613.7296665}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.802, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059613.7296665}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059613.8297322, "x": -88.23610474868231, "y": 40.0928242612778, "z": 202.53360372446207, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9087428162215616, "steering_wheel_angle": 8.97, "front_wheel_angle": 0.4767777037415168, "heading_rate": 0.7969773599994608, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059613.8296227}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.97, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059613.8296227}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059613.9298415, "x": -88.23610474868231, "y": 40.0928242612778, "z": 202.53360372446207, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9113268162215618, "steering_wheel_angle": 9.185, "front_wheel_angle": 0.49041299075004074, "heading_rate": 0.8279911886535668, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059613.9296389}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.185, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059613.9296389}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059614.0302787, "x": -88.23610474868231, "y": 40.0928242612778, "z": 202.53360372446207, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.919126816221562, "steering_wheel_angle": 9.409, "front_wheel_angle": 0.5047774817968852, "heading_rate": 0.8697906087712756, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059614.0296936}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.409, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059614.0296936}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059614.129723, "x": -88.23611955572468, "y": 40.09281459919714, "z": 202.51128295884172, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9048818162215615, "steering_wheel_angle": 9.591, "front_wheel_angle": 0.516571507410153, "heading_rate": 0.8697780009508377, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059614.1296225}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.591, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059614.1296225}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059614.2298777, "x": -88.23611955572468, "y": 40.09281459919714, "z": 202.51128295884172, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9061668162215617, "steering_wheel_angle": 9.685, "front_wheel_angle": 0.5227072044243146, "heading_rate": 0.8844988778556162, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059614.2296686}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.685, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059614.2296686}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059614.3299487, "x": -88.23611955572468, "y": 40.09281459919714, "z": 202.51128295884172, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9023178162215615, "steering_wheel_angle": 9.747, "front_wheel_angle": 0.526770956715711, "heading_rate": 0.8860123879556031, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059614.3297033}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.9, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.747, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059614.3297033}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059614.4297793, "x": -88.23611955572468, "y": 40.09281459919714, "z": 202.51128295884172, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8946738162215615, "steering_wheel_angle": 9.852, "front_wheel_angle": 0.5336840089435007, "heading_rate": 0.8863146970825906, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059614.4296331}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.84, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.852, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059614.4296331}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059614.5297484, "x": -88.23611955572468, "y": 40.09281459919714, "z": 202.51128295884172, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8883588162215617, "steering_wheel_angle": 9.942, "front_wheel_angle": 0.5396408311159901, "heading_rate": 0.8867141801447046, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059614.52963}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.79, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.942, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059614.52963}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059614.6297374, "x": -88.23612794293842, "y": 40.09280194325283, "z": 202.47327874245147, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8997618162215613, "steering_wheel_angle": 9.977, "front_wheel_angle": 0.5419652860962585, "heading_rate": 0.9125642114760663, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059614.629627}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.88, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.977, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059614.629627}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059614.7297165, "x": -88.23612794293842, "y": 40.09280194325283, "z": 202.47327874245147, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8972138162215613, "steering_wheel_angle": 9.978, "front_wheel_angle": 0.5420317646579869, "heading_rate": 0.9079968538588822, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059614.7296216}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.86, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.978, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059614.7296216}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059614.8297095, "x": -88.23612794293842, "y": 40.09280194325283, "z": 202.47327874245147, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8808468162215615, "steering_wheel_angle": 9.978, "front_wheel_angle": 0.5420317646579869, "heading_rate": 0.8774166489361737, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059614.8296201}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.73, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.978, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059614.8296201}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059614.9297566, "x": -88.23612794293842, "y": 40.09280194325283, "z": 202.47327874245147, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8721738162215615, "steering_wheel_angle": 9.98, "front_wheel_angle": 0.5421647327312799, "heading_rate": 0.8612094468918037, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059614.9296262}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.98, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059614.9296262}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059615.029707, "x": -88.23612794293842, "y": 40.09280194325283, "z": 202.47327874245147, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8883588162215617, "steering_wheel_angle": 9.988, "front_wheel_angle": 0.5426967511104958, "heading_rate": 0.8928726336140771, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059615.0296195}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.79, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.988, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059615.0296195}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059615.1298163, "x": -88.23613005046849, "y": 40.09278815307508, "z": 202.4959467746871, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8771178162215616, "steering_wheel_angle": 10.008, "front_wheel_angle": 0.5440278213488096, "heading_rate": 0.8742955257917739, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059615.1296518}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.7, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.008, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059615.1296518}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059615.229699, "x": -88.23613005046849, "y": 40.09278815307508, "z": 202.4959467746871, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8672618162215615, "steering_wheel_angle": 10.114, "front_wheel_angle": 0.5511071044505802, "heading_rate": 0.8691245434120101, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059615.2295716}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.114, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059615.2295716}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059615.3300085, "x": -88.23613005046849, "y": 40.09278815307508, "z": 202.4959467746871, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.858742816221562, "steering_wheel_angle": 10.181, "front_wheel_angle": 0.555603334236084, "heading_rate": 0.8609325323188391, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059615.3296857}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.55, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.181, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059615.3296857}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059615.4297698, "x": -88.23613005046849, "y": 40.09278815307508, "z": 202.4959467746871, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8672618162215615, "steering_wheel_angle": 10.19, "front_wheel_angle": 0.5562085923555132, "heading_rate": 0.8790948766250236, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059615.4296405}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.19, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059615.4296405}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059615.5297754, "x": -88.23613005046849, "y": 40.09278815307508, "z": 202.4959467746871, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8623818162215615, "steering_wheel_angle": 10.192, "front_wheel_angle": 0.5563431357343815, "heading_rate": 0.8696420110355915, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059615.5296347}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.192, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059615.5296347}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059615.6297817, "x": -88.23612679341798, "y": 40.0927753820769, "z": 202.4692178581, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8551218162215615, "steering_wheel_angle": 10.215, "front_wheel_angle": 0.5578914732789813, "heading_rate": 0.858022126839179, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059615.6296492}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.215, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059615.6296492}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059615.729754, "x": -88.23612679341798, "y": 40.0927753820769, "z": 202.4692178581, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8491268162215615, "steering_wheel_angle": 10.219, "front_wheel_angle": 0.5581609541917513, "heading_rate": 0.8463419067214336, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059615.7296298}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.47, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.219, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059615.7296298}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059615.8297734, "x": -88.23612679341798, "y": 40.0927753820769, "z": 202.4692178581, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8515188162215614, "steering_wheel_angle": 10.22, "front_wheel_angle": 0.5582283339172279, "heading_rate": 0.8513476328456603, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059615.829667}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.49, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.22, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059615.829667}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059615.929808, "x": -88.23612679341798, "y": 40.0927753820769, "z": 202.4692178581, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8515188162215614, "steering_wheel_angle": 10.22, "front_wheel_angle": 0.5582283339172279, "heading_rate": 0.8513476328456603, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059615.9296484}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.49, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.22, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059615.9296484}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059616.0297675, "x": -88.23612679341798, "y": 40.0927753820769, "z": 202.4692178581, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8491268162215615, "steering_wheel_angle": 10.22, "front_wheel_angle": 0.5582283339172279, "heading_rate": 0.8464688498494102, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059616.0296516}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.47, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.22, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059616.0296516}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059616.12988, "x": -88.23611823518033, "y": 40.09276473734289, "z": 202.4573824015894, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8479338162215617, "steering_wheel_angle": 10.22, "front_wheel_angle": 0.5582283339172279, "heading_rate": 0.844029458351285, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059616.129643}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.22, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059616.129643}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059616.2299137, "x": -88.23611823518033, "y": 40.09276473734289, "z": 202.4573824015894, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8491268162215615, "steering_wheel_angle": 10.22, "front_wheel_angle": 0.5582283339172279, "heading_rate": 0.8464688498494102, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059616.2296681}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.47, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.22, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059616.2296681}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059616.3297217, "x": -88.23611823518033, "y": 40.09276473734289, "z": 202.4573824015894, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8479338162215617, "steering_wheel_angle": 10.22, "front_wheel_angle": 0.5582283339172279, "heading_rate": 0.844029458351285, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059616.3296254}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.22, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059616.3296254}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059616.4297428, "x": -88.23611823518033, "y": 40.09276473734289, "z": 202.4573824015894, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8256468162215613, "steering_wheel_angle": 10.216, "front_wheel_angle": 0.5579588378100883, "heading_rate": 0.7972026146424089, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059616.4296508}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.27, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.216, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059616.4296508}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059616.529817, "x": -88.23611823518033, "y": 40.09276473734289, "z": 202.4573824015894, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8268018162215616, "steering_wheel_angle": 10.207, "front_wheel_angle": 0.5573526936677401, "heading_rate": 0.7985618245281783, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059616.5296597}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.207, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059616.5296597}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059616.6297374, "x": -88.2361057267583, "y": 40.09275698354182, "z": 202.40113762840352, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.822193816221562, "steering_wheel_angle": 10.207, "front_wheel_angle": 0.5573526936677401, "heading_rate": 0.788823265692469, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059616.6296482}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.207, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059616.6296482}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059616.7297704, "x": -88.2361057267583, "y": 40.09275698354182, "z": 202.40113762840352, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8130738162215616, "steering_wheel_angle": 10.207, "front_wheel_angle": 0.5573526936677401, "heading_rate": 0.76934614802105, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059616.729631}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.207, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059616.729631}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059616.829891, "x": -88.2361057267583, "y": 40.09275698354182, "z": 202.40113762840352, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8074388162215618, "steering_wheel_angle": 10.202, "front_wheel_angle": 0.5570160796668728, "heading_rate": 0.7566052797557158, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059616.8296704}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.11, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.202, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059616.8296704}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059616.9298437, "x": -88.2361057267583, "y": 40.09275698354182, "z": 202.40113762840352, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8302788162215617, "steering_wheel_angle": 10.134, "front_wheel_angle": 0.5524474995128235, "heading_rate": 0.7970865182080443, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059616.9296396}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.134, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059616.9296396}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059617.0297747, "x": -88.2361057267583, "y": 40.09275698354182, "z": 202.40113762840352, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8233428162215617, "steering_wheel_angle": 9.927, "front_wheel_angle": 0.538645998196493, "heading_rate": 0.7586599395022896, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059617.0296516}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.25, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.927, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059617.0296516}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059617.129716, "x": -88.23609147249924, "y": 40.0927528689034, "z": 202.36574292171252, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8130738162215616, "steering_wheel_angle": 9.732, "front_wheel_angle": 0.5257865568295523, "heading_rate": 0.7162720214503154, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059617.1296237}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.732, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059617.1296237}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059617.2300014, "x": -88.23609147249924, "y": 40.0927528689034, "z": 202.36574292171252, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8040818162215615, "steering_wheel_angle": 9.535, "front_wheel_angle": 0.5129306290344566, "heading_rate": 0.6776151772835444, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059617.2296498}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.535, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059617.2296498}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059617.3297427, "x": -88.23609147249924, "y": 40.0927528689034, "z": 202.36574292171252, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7963188162215618, "steering_wheel_angle": 9.156, "front_wheel_angle": 0.4885652333281108, "heading_rate": 0.6249825172209371, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059617.3296487}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.156, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059617.3296487}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059617.4300032, "x": -88.23609147249924, "y": 40.0927528689034, "z": 202.36574292171252, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7864818162215617, "steering_wheel_angle": 9.156, "front_wheel_angle": 0.4885652333281108, "heading_rate": 0.6062953323206434, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059617.4296534}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.156, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059617.4296534}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059617.5302196, "x": -88.23609147249924, "y": 40.0927528689034, "z": 202.36574292171252, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7810868162215616, "steering_wheel_angle": 7.837, "front_wheel_angle": 0.40720326251485967, "heading_rate": 0.483539146698672, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059617.529803}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.837, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059617.529803}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059617.6297348, "x": -88.23607667885778, "y": 40.09275196461063, "z": 202.37385123241552, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7930218162215614, "steering_wheel_angle": 7.081, "front_wheel_angle": 0.362714735404345, "heading_rate": 0.44176798865942746, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059617.6296294}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.081, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059617.6296294}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059617.729761, "x": -88.23607667885778, "y": 40.09275196461063, "z": 202.37385123241552, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7810868162215616, "steering_wheel_angle": 6.421, "front_wheel_angle": 0.32500830716045426, "heading_rate": 0.3777603939566824, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059617.7296565}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.421, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059617.7296565}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059617.8297243, "x": -88.23607667885778, "y": 40.09275196461063, "z": 202.37385123241552, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7652018162215617, "steering_wheel_angle": 5.806, "front_wheel_angle": 0.2907476604037157, "heading_rate": 0.31792890864189705, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059617.8296247}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.806, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059617.8296247}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059617.9297423, "x": -88.23607667885778, "y": 40.09275196461063, "z": 202.37385123241552, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7417188162215615, "steering_wheel_angle": 5.232, "front_wheel_angle": 0.25947997666775374, "heading_rate": 0.2582059916538543, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059617.9296474}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.49, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.232, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059617.9296474}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059618.029736, "x": -88.23607667885778, "y": 40.09275196461063, "z": 202.37385123241552, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7683428162215615, "steering_wheel_angle": 4.688, "front_wheel_angle": 0.23043904334398949, "heading_rate": 0.2520187259445069, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059618.029646}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.75, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.688, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059618.029646}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059618.1297498, "x": -88.23606205748261, "y": 40.09275240733149, "z": 202.3498246739302, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7269738162215615, "steering_wheel_angle": 4.111, "front_wheel_angle": 0.20022989516031572, "heading_rate": 0.1855084254550285, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059618.1296234}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.111, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059618.1296234}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059618.2299635, "x": -88.23606205748261, "y": 40.09275240733149, "z": 202.3498246739302, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7447218162215616, "steering_wheel_angle": 3.605, "front_wheel_angle": 0.17421364523982405, "heading_rate": 0.173247826964432, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059618.2297904}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.605, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059618.2297904}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059618.3297536, "x": -88.23606205748261, "y": 40.09275240733149, "z": 202.3498246739302, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7024818162215616, "steering_wheel_angle": 3.122, "front_wheel_angle": 0.1497737377284963, "heading_rate": 0.12260933380053562, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059618.3296282}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.122, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059618.3296282}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059618.4297466, "x": -88.23606205748261, "y": 40.09275240733149, "z": 202.3498246739302, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7033988162215614, "steering_wheel_angle": 3.122, "front_wheel_angle": 0.1497737377284963, "heading_rate": 0.12319880175149973, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059618.4296298}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.09, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.122, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059618.4296298}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059618.5298064, "x": -88.23606205748261, "y": 40.09275240733149, "z": 202.3498246739302, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6682788162215614, "steering_wheel_angle": 2.689, "front_wheel_angle": 0.12817631711089647, "heading_rate": 0.0850828548300976, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059618.529645}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.689, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059618.529645}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059618.629876, "x": -88.23604961948014, "y": 40.092753014182286, "z": 202.3442081702564, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6583668162215615, "steering_wheel_angle": 2.379, "front_wheel_angle": 0.11288864654116117, "heading_rate": 0.06952809327750083, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059618.6296437}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.379, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059618.6296437}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059618.7300196, "x": -88.23604961948014, "y": 40.092753014182286, "z": 202.3442081702564, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6333428162215617, "steering_wheel_angle": 2.099, "front_wheel_angle": 0.09920189175930116, "heading_rate": 0.04859794610839079, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059618.72968}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.25, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.099, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059618.72968}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059618.8298051, "x": -88.23604961948014, "y": 40.092753014182286, "z": 202.3442081702564, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6187428162215616, "steering_wheel_angle": 1.762, "front_wheel_angle": 0.08287763808139191, "heading_rate": 0.03407082444519569, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059618.829666}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.762, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059618.829666}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059618.929733, "x": -88.23604961948014, "y": 40.092753014182286, "z": 202.3442081702564, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6029418162215614, "steering_wheel_angle": 1.39, "front_wheel_angle": 0.06504129729450868, "heading_rate": 0.020862968200700122, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059618.9296246}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.39, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059618.9296246}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059619.0299733, "x": -88.23604961948014, "y": 40.092753014182286, "z": 202.3442081702564, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5875818162215616, "steering_wheel_angle": 1.121, "front_wheel_angle": 0.05226004893410875, "heading_rate": 0.01185095806892181, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059619.0296552}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.121, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059619.0296552}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059619.129793, "x": -88.23604283788306, "y": 40.09275341708834, "z": 202.37076275932276, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5773988162215615, "steering_wheel_angle": 0.873, "front_wheel_angle": 0.04056110827789295, "heading_rate": 0.006499679820647146, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059619.129631}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.873, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059619.129631}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059619.2297401, "x": -88.23604283788306, "y": 40.09275341708834, "z": 202.37076275932276, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5640068162215615, "steering_wheel_angle": 0.648, "front_wheel_angle": 0.030015875725911266, "heading_rate": 0.001993840568803518, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059619.2296262}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.17, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.648, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059619.2296262}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059619.3297198, "x": -88.23604283788306, "y": 40.09275341708834, "z": 202.37076275932276, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5582538162215616, "steering_wheel_angle": 0.458, "front_wheel_angle": 0.021161017395111472, "heading_rate": 0.0004960353870815955, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059619.3296244}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.458, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059619.3296244}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059619.4297433, "x": -88.23604283788306, "y": 40.09275341708834, "z": 202.37076275932276, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5567268162215617, "steering_wheel_angle": 0.326, "front_wheel_angle": 0.015035780428628494, "heading_rate": 0.00017621383126074062, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059619.4296453}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.326, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059619.4296453}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059619.5297337, "x": -88.23604283788306, "y": 40.09275341708834, "z": 202.37076275932276, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5562218162215617, "steering_wheel_angle": 0.277, "front_wheel_angle": 0.012767505289246275, "heading_rate": 9.975155527125854e-05, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059619.5296423}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059619.5296423}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059619.629734, "x": -88.23604185223495, "y": 40.092753521152645, "z": 202.39172129406492, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5557188162215616, "steering_wheel_angle": 0.256, "front_wheel_angle": 0.011796291943346152, "heading_rate": 4.608140287105141e-05, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059619.6296358}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.256, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059619.6296358}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059619.7298055, "x": -88.23604185223495, "y": 40.092753521152645, "z": 202.39172129406492, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.257, "front_wheel_angle": 0.011842527913388357, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059619.7297132}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.257, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059619.7297132}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059619.829755, "x": -88.23604185223495, "y": 40.092753521152645, "z": 202.39172129406492, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.264, "front_wheel_angle": 0.012166214088474283, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059619.8296504}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.264, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059619.8296504}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059619.929933, "x": -88.23604185223495, "y": 40.092753521152645, "z": 202.39172129406492, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.277, "front_wheel_angle": 0.012767505289246275, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059619.929646}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059619.929646}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059620.0298355, "x": -88.23604185223495, "y": 40.092753521152645, "z": 202.39172129406492, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.25, "front_wheel_angle": 0.011518901902098604, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059620.0296896}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.25, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059620.0296896}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059620.1297557, "x": -88.23604240699, "y": 40.092753460474746, "z": 202.377639920909, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.208, "front_wheel_angle": 0.009578407398255724, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059620.1296177}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.208, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059620.1296177}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059620.2297142, "x": -88.23604240699, "y": 40.092753460474746, "z": 202.377639920909, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5582538162215616, "steering_wheel_angle": 0.227, "front_wheel_angle": 0.01045598248001368, "heading_rate": 0.0002450710204467651, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059620.2296147}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.227, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059620.2296147}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059620.3297157, "x": -88.23604240699, "y": 40.092753460474746, "z": 202.377639920909, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5711178162215615, "steering_wheel_angle": 0.24, "front_wheel_angle": 0.011056683328117477, "heading_rate": 0.0012957578801840747, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059620.3296154}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.24, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059620.3296154}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059620.4297185, "x": -88.23604240699, "y": 40.092753460474746, "z": 202.377639920909, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5577428162215616, "steering_wheel_angle": 0.235, "front_wheel_angle": 0.01082562002866119, "heading_rate": 0.00021144615132619854, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059620.4296057}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.235, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059620.4296057}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059620.5297937, "x": -88.23604240699, "y": 40.092753460474746, "z": 202.377639920909, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5739428162215616, "steering_wheel_angle": 0.194, "front_wheel_angle": 0.00893205569068718, "heading_rate": 0.0012212119658897463, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059620.5296516}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.35, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.194, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059620.5296516}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059620.6299102, "x": -88.23604229548818, "y": 40.09275349019439, "z": 202.37704864255466, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5629428162215615, "steering_wheel_angle": 0.146, "front_wheel_angle": 0.006717808943590281, "heading_rate": 0.00039362753913973765, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059620.629687}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.146, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059620.629687}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059620.7298334, "x": -88.23604229548818, "y": 40.09275349019439, "z": 202.37704864255466, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.593206816221562, "steering_wheel_angle": 0.142, "front_wheel_angle": 0.006533415102241901, "heading_rate": 0.0017099415637700005, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059620.7296271}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.142, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059620.7296271}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059620.8297248, "x": -88.23604229548818, "y": 40.09275349019439, "z": 202.37704864255466, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5791538162215617, "steering_wheel_angle": 0.138, "front_wheel_angle": 0.006349040727595683, "heading_rate": 0.0010912560380542755, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059620.8296204}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.138, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059620.8296204}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059620.9297626, "x": -88.23604229548818, "y": 40.09275349019439, "z": 202.37704864255466, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6083178162215614, "steering_wheel_angle": 0.095, "front_wheel_angle": 0.004368243991637956, "heading_rate": 0.0015357205463016263, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059620.9296362}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.095, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059620.9296362}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059621.02971, "x": -88.23604229548818, "y": 40.09275349019439, "z": 202.37704864255466, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6131268162215617, "steering_wheel_angle": 0.032, "front_wheel_angle": 0.0014701917131421402, "heading_rate": 0.0005570652301665747, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059621.029616}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.032, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059621.029616}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059621.1297748, "x": -88.2360391405266, "y": 40.09275357084987, "z": 202.37079318954233, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6281418162215617, "steering_wheel_angle": 0.018, "front_wheel_angle": 0.0008268310472349244, "heading_rate": 0.00038111752268513014, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059621.1296222}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.018, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059621.1296222}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059621.2297313, "x": -88.2360391405266, "y": 40.09275357084987, "z": 202.37079318954233, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6575538162215615, "steering_wheel_angle": 0.037, "front_wheel_angle": 0.0017000206580417147, "heading_rate": 0.0010359510864848297, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059621.2296233}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.037, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059621.2296233}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059621.329709, "x": -88.2360391405266, "y": 40.09275357084987, "z": 202.37079318954233, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6559338162215615, "steering_wheel_angle": 0.042, "front_wheel_angle": 0.0019298797685140421, "heading_rate": 0.0011609447395351832, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059621.329615}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.54, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.042, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059621.329615}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059621.4297764, "x": -88.2360391405266, "y": 40.09275357084987, "z": 202.37079318954233, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6997428162215615, "steering_wheel_angle": 0.044, "front_wheel_angle": 0.002021831861724432, "heading_rate": 0.0016190472516381042, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059621.4296248}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.044, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059621.4296248}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059621.5298798, "x": -88.2360391405266, "y": 40.09275357084987, "z": 202.37079318954233, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7024818162215616, "steering_wheel_angle": 0.058, "front_wheel_angle": 0.0026656317731134417, "heading_rate": 0.0021658309454946558, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059621.5296745}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.058, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059621.5296745}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059621.6297665, "x": -88.23602968408373, "y": 40.092753742917544, "z": 202.3803808340734, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7279428162215615, "steering_wheel_angle": 0.062, "front_wheel_angle": 0.0028496181038668014, "heading_rate": 0.002615867449350977, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059621.6296291}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.35, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.062, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059621.6296291}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059621.7297328, "x": -88.23602968408373, "y": 40.092753742917544, "z": 202.3803808340734, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7579428162215613, "steering_wheel_angle": 0.059, "front_wheel_angle": 0.002711626542631913, "heading_rate": 0.002806964043067308, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059621.729621}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.059, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059621.729621}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059621.8297436, "x": -88.23602968408373, "y": 40.092753742917544, "z": 202.3803808340734, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7736178162215617, "steering_wheel_angle": 0.059, "front_wheel_angle": 0.002711626542631913, "heading_rate": 0.0029658488002220615, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059621.8296492}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.8, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.059, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059621.8296492}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059621.929733, "x": -88.23602968408373, "y": 40.092753742917544, "z": 202.3803808340734, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8007428162215615, "steering_wheel_angle": 0.059, "front_wheel_angle": 0.002711626542631913, "heading_rate": 0.0032306567288133167, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059621.9296205}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.059, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059621.9296205}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059622.0298069, "x": -88.23602968408373, "y": 40.092753742917544, "z": 202.3803808340734, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8268018162215616, "steering_wheel_angle": 0.059, "front_wheel_angle": 0.002711626542631913, "heading_rate": 0.003474280023117272, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059622.0296345}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.059, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059622.0296345}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059622.130104, "x": -88.23602968408373, "y": 40.092753742917544, "z": 202.3803808340734, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8503218162215616, "steering_wheel_angle": 0.059, "front_wheel_angle": 0.002711626542631913, "heading_rate": 0.003686126365990277, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059622.1296368}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.059, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059622.1296368}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059622.2299032, "x": -88.23601336501288, "y": 40.092754102480214, "z": 202.39272680408732, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8921418162215615, "steering_wheel_angle": 0.059, "front_wheel_angle": 0.002711626542631913, "heading_rate": 0.004046265148874384, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059622.229638}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.059, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059622.229638}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059622.3297915, "x": -88.23601336501288, "y": 40.092754102480214, "z": 202.39272680408732, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9243668162215615, "steering_wheel_angle": 0.059, "front_wheel_angle": 0.002711626542631913, "heading_rate": 0.004311073077465639, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059622.3296485}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.059, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059622.3296485}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059622.4298272, "x": -88.23601336501288, "y": 40.092754102480214, "z": 202.39272680408732, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9537588162215616, "steering_wheel_angle": 0.059, "front_wheel_angle": 0.002711626542631913, "heading_rate": 0.004544104054625945, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059622.4296584}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.29, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.059, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059622.4296584}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059622.5298076, "x": -88.23601336501288, "y": 40.092754102480214, "z": 202.39272680408732, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.975742816221562, "steering_wheel_angle": 0.059, "front_wheel_angle": 0.002711626542631913, "heading_rate": 0.004713581128924348, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059622.5296195}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.45, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.059, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059622.5296195}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059622.629744, "x": -88.23599035101522, "y": 40.0927546724011, "z": 202.3944496174031, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": 0.059, "front_wheel_angle": 0.002711626542631913, "heading_rate": 0.004936019788941003, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059622.6296256}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.059, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059622.6296256}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059622.7297916, "x": -88.23599035101522, "y": 40.0927546724011, "z": 202.3944496174031, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.038838816221562, "steering_wheel_angle": 0.059, "front_wheel_angle": 0.002711626542631913, "heading_rate": 0.005179643083244957, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059622.7296512}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.059, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059622.7296512}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059622.8298156, "x": -88.23599035101522, "y": 40.0927546724011, "z": 202.3944496174031, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": 0.059, "front_wheel_angle": 0.002711626542631913, "heading_rate": 0.005455043328979864, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059622.82964}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.059, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059622.82964}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059622.9298487, "x": -88.23599035101522, "y": 40.0927546724011, "z": 202.3944496174031, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": 0.059, "front_wheel_angle": 0.002711626542631913, "heading_rate": 0.00571985125757112, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059622.9296262}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.059, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059622.9296262}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059623.029786, "x": -88.23599035101522, "y": 40.0927546724011, "z": 202.3944496174031, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": 0.059, "front_wheel_angle": 0.002711626542631913, "heading_rate": 0.0058045897947203206, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059623.0296412}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.059, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059623.0296412}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059623.1297781, "x": -88.2359607993746, "y": 40.09275550230389, "z": 202.35436862751246, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": 0.059, "front_wheel_angle": 0.002711626542631913, "heading_rate": 0.005974066869018723, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059623.129643}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.059, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059623.129643}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059623.2297559, "x": -88.2359607993746, "y": 40.09275550230389, "z": 202.35436862751246, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.183278816221561, "steering_wheel_angle": 0.059, "front_wheel_angle": 0.002711626542631913, "heading_rate": 0.006154136260460777, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059623.229646}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.059, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059623.229646}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059623.3300185, "x": -88.2359607993746, "y": 40.09275550230389, "z": 202.35436862751246, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.223742816221561, "steering_wheel_angle": 0.059, "front_wheel_angle": 0.002711626542631913, "heading_rate": 0.006408351871908383, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059623.3297293}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.059, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059623.3297293}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059623.4298918, "x": -88.2359607993746, "y": 40.09275550230389, "z": 202.35436862751246, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.2531018162215615, "steering_wheel_angle": 0.058, "front_wheel_angle": 0.0026656317731134417, "heading_rate": 0.006476667538931134, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059623.4296634}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.058, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059623.4296634}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059623.5297241, "x": -88.2359607993746, "y": 40.09275550230389, "z": 202.35436862751246, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": 0.045, "front_wheel_angle": 0.002067809719214362, "heading_rate": 0.0051533768796065416, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059623.529616}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.045, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059623.529616}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059623.6297786, "x": -88.23592582426156, "y": 40.09275665004913, "z": 202.32442800077158, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3099338162215615, "steering_wheel_angle": 0.025, "front_wheel_angle": 0.0011484818458397522, "heading_rate": 0.0029340135055421117, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059623.6296265}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.54, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059623.6296265}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059623.729741, "x": -88.23592582426156, "y": 40.09275665004913, "z": 202.32442800077158, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.324461816221562, "steering_wheel_angle": 0.003, "front_wheel_angle": 0.00013777808953256048, "heading_rate": 0.00035628553065503816, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059623.7296154}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.003, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059623.7296154}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059623.8298166, "x": -88.23592582426156, "y": 40.09275665004913, "z": 202.32442800077158, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.355758816221561, "steering_wheel_angle": -0.001, "front_wheel_angle": -4.592482660220106e-05, "heading_rate": -0.00012180842689381667, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059623.8296247}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.001, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059623.8296247}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059623.929825, "x": -88.23592582426156, "y": 40.09275665004913, "z": 202.32442800077158, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": -0.014, "front_wheel_angle": -0.0006430570990113664, "heading_rate": -0.0017257042496725138, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059623.929627}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.014, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059623.929627}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059624.0300727, "x": -88.23592582426156, "y": 40.09275665004913, "z": 202.32442800077158, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.00511451521142301, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059624.0296788}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059624.0296788}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059624.1299338, "x": -88.23588687629127, "y": 40.092757936063194, "z": 202.34513236393815, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.400926816221562, "steering_wheel_angle": -0.053, "front_wheel_angle": -0.0024356760529297954, "heading_rate": -0.00668860801274252, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059624.129625}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.053, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059624.129625}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059624.2297232, "x": -88.23588687629127, "y": 40.092757936063194, "z": 202.34513236393815, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": -0.051, "front_wheel_angle": -0.002343702222536118, "heading_rate": -0.006591674570111793, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059624.2296133}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059624.2296133}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059624.3297417, "x": -88.23588687629127, "y": 40.092757936063194, "z": 202.34513236393815, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.449201816221562, "steering_wheel_angle": -0.048, "front_wheel_angle": -0.0022057505363656986, "heading_rate": -0.006272613260582432, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059624.329644}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.048, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059624.329644}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059624.4297118, "x": -88.23588687629127, "y": 40.092757936063194, "z": 202.34513236393815, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.464913816221562, "steering_wheel_angle": -0.053, "front_wheel_angle": -0.0024356760529297954, "heading_rate": -0.0070025824998271625, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059624.4296138}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.053, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059624.4296138}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059624.5297425, "x": -88.23588687629127, "y": 40.092757936063194, "z": 202.34513236393815, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.496721816221561, "steering_wheel_angle": -0.059, "front_wheel_angle": -0.002711626542631913, "heading_rate": -0.007965422492024966, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059624.5296419}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.059, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059624.5296419}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059624.6298292, "x": -88.23584493632595, "y": 40.09275948138859, "z": 202.3385976770766, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.514838816221562, "steering_wheel_angle": -0.064, "front_wheel_angle": -0.0029416185228755055, "heading_rate": -0.008744445909401427, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059624.6296628}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.064, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059624.6296628}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059624.730179, "x": -88.23584493632595, "y": 40.09275948138859, "z": 202.3385976770766, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.514838816221562, "steering_wheel_angle": -0.076, "front_wheel_angle": -0.003493722635840881, "heading_rate": -0.010385678685436701, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059624.7297115}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.076, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059624.7297115}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059624.8298042, "x": -88.23584493632595, "y": 40.09275948138859, "z": 202.3385976770766, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.531078816221561, "steering_wheel_angle": -0.079, "front_wheel_angle": -0.003631775890244649, "heading_rate": -0.010909562260314705, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059624.8296661}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.079, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059624.8296661}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059624.9297879, "x": -88.23584493632595, "y": 40.09275948138859, "z": 202.3385976770766, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.563942816221561, "steering_wheel_angle": -0.074, "front_wheel_angle": -0.0034016931847546217, "heading_rate": -0.010431013476559947, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059624.9296424}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.074, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059624.9296424}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059625.0297477, "x": -88.23584493632595, "y": 40.09275948138859, "z": 202.3385976770766, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.563942816221561, "steering_wheel_angle": -0.077, "front_wheel_angle": -0.0035397391768435885, "heading_rate": -0.010854323669280682, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059625.029648}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.077, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059625.029648}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059625.1297443, "x": -88.23580030443802, "y": 40.0927611730359, "z": 202.35741811486807, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.580566816221562, "steering_wheel_angle": -0.077, "front_wheel_angle": -0.0035397391768435885, "heading_rate": -0.010964940980559975, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059625.129644}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.077, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059625.129644}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059625.2297137, "x": -88.23580030443802, "y": 40.0927611730359, "z": 202.35741811486807, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": -0.077, "front_wheel_angle": -0.0035397391768435885, "heading_rate": -0.01108938545574918, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059625.229614}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.077, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059625.229614}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059625.3297284, "x": -88.23580030443802, "y": 40.0927611730359, "z": 202.35741811486807, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.633341816221561, "steering_wheel_angle": -0.077, "front_wheel_angle": -0.0035397391768435885, "heading_rate": -0.011310620078307767, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059625.3296397}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.077, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059625.3296397}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059625.4297047, "x": -88.23580030443802, "y": 40.0927611730359, "z": 202.35741811486807, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.650493816221561, "steering_wheel_angle": -0.088, "front_wheel_angle": -0.004046001037507012, "heading_rate": -0.013054746458600122, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059625.4296124}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.26, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.088, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059625.4296124}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059625.5300562, "x": -88.23580030443802, "y": 40.0927611730359, "z": 202.35741811486807, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.650493816221561, "steering_wheel_angle": -0.084, "front_wheel_angle": -0.0038618888613507667, "heading_rate": -0.012460687726266732, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059625.529654}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.26, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.084, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059625.529654}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059625.6297672, "x": -88.23575333822644, "y": 40.09276256359778, "z": 202.33996447144636, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.667773816221562, "steering_wheel_angle": -0.084, "front_wheel_angle": -0.0038618888613507667, "heading_rate": -0.012581372353155516, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059625.6296513}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.084, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059625.6296513}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059625.7297301, "x": -88.23575333822644, "y": 40.09276256359778, "z": 202.33996447144636, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.667773816221562, "steering_wheel_angle": -0.083, "front_wheel_angle": -0.003815863845306958, "heading_rate": -0.012431429270852725, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059625.729617}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.083, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059625.729617}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059625.829705, "x": -88.23575333822644, "y": 40.09276256359778, "z": 202.33996447144636, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.687366816221561, "steering_wheel_angle": -0.082, "front_wheel_angle": -0.003769840040269683, "heading_rate": -0.012414024253266896, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059625.8296103}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.082, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059625.8296103}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059625.9297528, "x": -88.23575333822644, "y": 40.09276256359778, "z": 202.33996447144636, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.704918816221562, "steering_wheel_angle": -0.081, "front_wheel_angle": -0.0037238174461442725, "heading_rate": -0.012378840994474458, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059625.929657}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.51, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.081, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059625.929657}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059626.0297449, "x": -88.23575333822644, "y": 40.09276256359778, "z": 202.33996447144636, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.722598816221561, "steering_wheel_angle": -0.077, "front_wheel_angle": -0.0035397391768435885, "heading_rate": -0.011877533798614148, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059626.029644}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.59, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.077, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059626.029644}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059626.1297054, "x": -88.2357042078181, "y": 40.09276363168405, "z": 202.34042088977733, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.740406816221562, "steering_wheel_angle": -0.077, "front_wheel_angle": -0.0035397391768435885, "heading_rate": -0.01198815110989344, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059626.1296115}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.077, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059626.1296115}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059626.2298012, "x": -88.2357042078181, "y": 40.09276363168405, "z": 202.34042088977733, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.758342816221561, "steering_wheel_angle": -0.074, "front_wheel_angle": -0.0034016931847546217, "heading_rate": -0.011626925849668731, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059626.2296557}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.75, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.074, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059626.2296557}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059626.3299766, "x": -88.2357042078181, "y": 40.09276363168405, "z": 202.34042088977733, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.758342816221561, "steering_wheel_angle": -0.071, "front_wheel_angle": -0.00326365808398965, "heading_rate": -0.011155120947913018, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059626.3296602}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.75, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.071, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059626.3296602}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059626.4299307, "x": -88.2357042078181, "y": 40.09276363168405, "z": 202.34042088977733, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.776406816221561, "steering_wheel_angle": -0.064, "front_wheel_angle": -0.0029416185228755055, "heading_rate": -0.01014631503022531, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059626.4296792}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.064, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059626.4296792}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059626.5297868, "x": -88.2357042078181, "y": 40.09276363168405, "z": 202.34042088977733, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.776406816221561, "steering_wheel_angle": -0.047, "front_wheel_angle": -0.0021597690564398976, "heading_rate": -0.007449527508173813, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059626.5296545}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.047, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059626.5296545}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059626.6298232, "x": -88.23565331352435, "y": 40.0927647696329, "z": 202.3785119365285, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.796881816221561, "steering_wheel_angle": -0.024, "front_wheel_angle": -0.0011025281160615484, "heading_rate": -0.0038416229609870454, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059626.6296246}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.024, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059626.6296246}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059626.7297332, "x": -88.23565331352435, "y": 40.0927647696329, "z": 202.3785119365285, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.796881816221561, "steering_wheel_angle": -0.012, "front_wheel_angle": -0.0005511773519229937, "heading_rate": -0.0019205087800879498, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059626.7296379}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.012, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059626.7296379}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059626.8297255, "x": -88.23565331352435, "y": 40.0927647696329, "z": 202.3785119365285, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.815217816221562, "steering_wheel_angle": -0.008, "front_wheel_angle": -0.00036743230800517036, "heading_rate": -0.0012917542659624187, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059626.829637}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.008, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059626.829637}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059626.929736, "x": -88.23565331352435, "y": 40.0927647696329, "z": 202.3785119365285, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.833681816221562, "steering_wheel_angle": -0.004, "front_wheel_angle": -0.00018370652604977013, "heading_rate": -0.000651584091912684, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059626.929641}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.004, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059626.929641}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059627.0297897, "x": -88.23565331352435, "y": 40.0927647696329, "z": 202.3785119365285, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.833681816221562, "steering_wheel_angle": -0.003, "front_wheel_angle": -0.00013777808953256048, "heading_rate": -0.000488681664402983, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059627.029652}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.003, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059627.029652}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059627.1297758, "x": -88.23560125603647, "y": 40.09276607860793, "z": 202.37435102509082, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.833681816221562, "steering_wheel_angle": -0.001, "front_wheel_angle": -4.592482660220106e-05, "heading_rate": -0.00016288961946919812, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059627.1296494}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.001, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059627.1296494}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059627.2301276, "x": -88.23560125603647, "y": 40.09276607860793, "z": 202.37435102509082, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.852273816221562, "steering_wheel_angle": 0.002, "front_wheel_angle": 9.1850856414927e-05, "heading_rate": 0.0003286538465338988, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059627.2296586}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.002, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059627.2296586}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059627.3297596, "x": -88.23560125603647, "y": 40.09276607860793, "z": 202.37435102509082, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.870993816221562, "steering_wheel_angle": 0.007, "front_wheel_angle": 0.00032149905694411315, "heading_rate": 0.001160410698638311, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059627.3296232}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.007, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059627.3296232}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059627.4297557, "x": -88.23560125603647, "y": 40.09276607860793, "z": 202.37435102509082, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": 0.013, "front_wheel_angle": 0.0005971166232941916, "heading_rate": 0.0021762104521315167, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059627.4296176}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059627.4296176}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059627.529755, "x": -88.23560125603647, "y": 40.09276607860793, "z": 202.37435102509082, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": 0.015, "front_wheel_angle": 0.0006889987791691868, "heading_rate": 0.002511077979246371, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059627.5296204}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059627.5296204}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059627.6297457, "x": -88.23554805104554, "y": 40.092767469564116, "z": 202.37995007768507, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": 0.018, "front_wheel_angle": 0.0008268310472349244, "heading_rate": 0.0030134122768239527, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059627.6296368}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.018, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059627.6296368}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059627.7297559, "x": -88.23554805104554, "y": 40.092767469564116, "z": 202.37995007768507, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.911198816221562, "steering_wheel_angle": 0.024, "front_wheel_angle": 0.0011025281160615484, "heading_rate": 0.004052653818709428, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059627.7296448}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.024, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059627.7296448}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059627.829751, "x": -88.23554805104554, "y": 40.092767469564116, "z": 202.37995007768507, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.930318816221561, "steering_wheel_angle": 0.053, "front_wheel_angle": 0.0024356760529297954, "heading_rate": 0.009029145098282577, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059627.8296425}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.49, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.053, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059627.8296425}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059627.9297726, "x": -88.23554805104554, "y": 40.092767469564116, "z": 202.37995007768507, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.930318816221561, "steering_wheel_angle": 0.084, "front_wheel_angle": 0.0038618888613507667, "heading_rate": 0.014316213864681756, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059627.9296186}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.49, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.084, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059627.9296186}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059628.0298579, "x": -88.23554805104554, "y": 40.092767469564116, "z": 202.37995007768507, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.911198816221562, "steering_wheel_angle": 0.084, "front_wheel_angle": 0.0038618888613507667, "heading_rate": 0.014195529237792973, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059628.029626}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.084, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059628.029626}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059628.1297584, "x": -88.23549388816618, "y": 40.09276901996588, "z": 202.39496989578979, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.911198816221562, "steering_wheel_angle": 0.078, "front_wheel_angle": 0.0035857569282793833, "heading_rate": 0.01318051457423519, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059628.1296444}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.078, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059628.1296444}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059628.229769, "x": -88.23549388816618, "y": 40.09276901996588, "z": 202.39496989578979, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.870993816221562, "steering_wheel_angle": 0.079, "front_wheel_angle": 0.003631775890244649, "heading_rate": 0.013108498736711036, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059628.2296267}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.079, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059628.2296267}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059628.3297093, "x": -88.23549388816618, "y": 40.09276901996588, "z": 202.39496989578979, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.870993816221562, "steering_wheel_angle": 0.079, "front_wheel_angle": 0.003631775890244649, "heading_rate": 0.013108498736711036, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059628.3296113}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.079, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059628.3296113}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059628.4297569, "x": -88.23549388816618, "y": 40.09276901996588, "z": 202.39496989578979, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.852273816221562, "steering_wheel_angle": 0.077, "front_wheel_angle": 0.0035397391768435885, "heading_rate": 0.012665682141479114, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059628.4296443}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.077, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059628.4296443}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059628.529741, "x": -88.23549388816618, "y": 40.09276901996588, "z": 202.39496989578979, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.870993816221562, "steering_wheel_angle": 0.07, "front_wheel_angle": 0.0032176488035831207, "heading_rate": 0.011613741230502801, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059628.5296414}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.07, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059628.5296414}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059628.629908, "x": -88.2354398220421, "y": 40.09277095306541, "z": 202.39734942043444, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.870993816221562, "steering_wheel_angle": 0.061, "front_wheel_angle": 0.002803619707913495, "heading_rate": 0.01011934139689479, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059628.6296384}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.061, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059628.6296384}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059628.729781, "x": -88.2354398220421, "y": 40.09277095306541, "z": 202.39734942043444, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.815217816221562, "steering_wheel_angle": 0.027, "front_wheel_angle": 0.0012403929219419797, "heading_rate": 0.00436075860265331, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059628.7296543}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.027, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059628.7296543}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059628.8297398, "x": -88.2354398220421, "y": 40.09277095306541, "z": 202.39734942043444, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.704918816221562, "steering_wheel_angle": 0.004, "front_wheel_angle": 0.00018370652604977013, "heading_rate": 0.0006106806852617777, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059628.8296342}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.51, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.004, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059628.8296342}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059628.9297826, "x": -88.2354398220421, "y": 40.09277095306541, "z": 202.39734942043444, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.580566816221562, "steering_wheel_angle": -0.003, "front_wheel_angle": -0.00013777808953256048, "heading_rate": -0.0004267891628541469, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059628.929661}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.003, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059628.929661}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059629.0298238, "x": -88.2354398220421, "y": 40.09277095306541, "z": 202.39734942043444, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": -0.009, "front_wheel_angle": -0.00041336676293914716, "heading_rate": -0.0013079183478577226, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059629.029623}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.009, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059629.029623}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059629.1297336, "x": -88.235389902956, "y": 40.09277316885829, "z": 202.34343414896978, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.480753816221561, "steering_wheel_angle": -0.01, "front_wheel_angle": -0.0004593024218401402, "heading_rate": -0.0013348477573388313, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059629.1296146}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.01, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059629.1296146}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059629.2297118, "x": -88.235389902956, "y": 40.09277316885829, "z": 202.34343414896978, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": -0.011, "front_wheel_angle": -0.0005052392848031042, "heading_rate": -0.0014209856094188514, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059629.2296073}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.011, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059629.2296073}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059629.3298995, "x": -88.235389902956, "y": 40.09277316885829, "z": 202.34343414896978, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.324461816221562, "steering_wheel_angle": -0.011, "front_wheel_angle": -0.0005052392848031042, "heading_rate": -0.0013065173242156661, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059629.329668}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.011, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059629.329668}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059629.4298096, "x": -88.235389902956, "y": 40.09277316885829, "z": 202.34343414896978, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": -0.014, "front_wheel_angle": -0.0006430570990113664, "heading_rate": -0.0016227146219628004, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059629.4296594}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.014, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059629.4296594}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059629.5298262, "x": -88.235389902956, "y": 40.09277316885829, "z": 202.34343414896978, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.183278816221561, "steering_wheel_angle": -0.018, "front_wheel_angle": -0.0008268310472349244, "heading_rate": -0.0018765193277971237, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059629.5296483}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.018, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059629.5296483}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059629.6299918, "x": -88.2353496709379, "y": 40.09277484197072, "z": 202.31119543971047, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": -0.018, "front_wheel_angle": -0.0008268310472349244, "heading_rate": -0.0018216125660543508, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059629.629638}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.018, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059629.629638}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059629.7298455, "x": -88.2353496709379, "y": 40.09277484197072, "z": 202.31119543971047, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": -0.018, "front_wheel_angle": -0.0008268310472349244, "heading_rate": -0.0016116749476261013, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059629.7296555}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.018, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059629.7296555}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059629.8297815, "x": -88.2353496709379, "y": 40.09277484197072, "z": 202.31119543971047, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": -0.019, "front_wheel_angle": -0.000872777546103444, "heading_rate": -0.0016160025855321294, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059629.8296683}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.019, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059629.8296683}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059629.929847, "x": -88.2353496709379, "y": 40.09277484197072, "z": 202.31119543971047, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9269988162215617, "steering_wheel_angle": -0.021, "front_wheel_angle": -0.0009646741586794069, "heading_rate": -0.0015412181769116188, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059629.9296424}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.09, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.021, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059629.9296424}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059630.0297568, "x": -88.2353496709379, "y": 40.09277484197072, "z": 202.31119543971047, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.887101816221562, "steering_wheel_angle": -0.026, "front_wheel_angle": -0.001194436781101673, "heading_rate": -0.0017636613983218771, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059630.02966}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.78, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059630.02966}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059630.1297727, "x": -88.23532194734605, "y": 40.09277583367621, "z": 202.30238203094603, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8349428162215617, "steering_wheel_angle": -0.027, "front_wheel_angle": -0.0012403929219419797, "heading_rate": -0.0016231712576542877, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059630.1296434}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.35, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059630.1296434}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059630.2297568, "x": -88.23532194734605, "y": 40.09277583367621, "z": 202.30238203094603, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.789742816221562, "steering_wheel_angle": -0.027, "front_wheel_angle": -0.0012403929219419797, "heading_rate": -0.0014293597642030297, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059630.229633}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059630.229633}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059630.3298864, "x": -88.23532194734605, "y": 40.09277583367621, "z": 202.30238203094603, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7487538162215617, "steering_wheel_angle": -0.027, "front_wheel_angle": -0.0012403929219419797, "heading_rate": -0.0012403935580880528, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059630.3296607}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059630.3296607}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059630.4297948, "x": -88.23532194734605, "y": 40.09277583367621, "z": 202.30238203094603, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7061618162215617, "steering_wheel_angle": -0.027, "front_wheel_angle": -0.0012403929219419797, "heading_rate": -0.0010272009152916689, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059630.429639}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059630.429639}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059630.5300062, "x": -88.23532194734605, "y": 40.09277583367621, "z": 202.30238203094603, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6819428162215617, "steering_wheel_angle": -0.028, "front_wheel_angle": -0.0012863502684559124, "heading_rate": -0.0009295895739185967, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059630.5296786}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.028, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059630.5296786}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059630.6298134, "x": -88.23530648399841, "y": 40.09277650680743, "z": 202.30223467728095, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6417138162215617, "steering_wheel_angle": -0.028, "front_wheel_angle": -0.0012863502684559124, "heading_rate": -0.0006833739570428602, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059630.6296437}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.028, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059630.6296437}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059630.7297297, "x": -88.23530648399841, "y": 40.09277650680743, "z": 202.30223467728095, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6201668162215617, "steering_wheel_angle": -0.028, "front_wheel_angle": -0.0012863502684559124, "heading_rate": -0.0005376545103204857, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059630.729635}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.028, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059630.729635}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059630.8297563, "x": -88.23530648399841, "y": 40.09277650680743, "z": 202.30223467728095, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.593206816221562, "steering_wheel_angle": -0.028, "front_wheel_angle": -0.0012863502684559124, "heading_rate": -0.000336662170013762, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059630.8296125}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.028, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059630.8296125}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059630.9297192, "x": -88.23530648399841, "y": 40.09277650680743, "z": 202.30223467728095, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5750868162215617, "steering_wheel_angle": -0.028, "front_wheel_angle": -0.0012863502684559124, "heading_rate": -0.0001859179147837193, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059630.9296079}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.37, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.028, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059630.9296079}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059631.0297863, "x": -88.23530648399841, "y": 40.09277650680743, "z": 202.30223467728095, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5603178162215614, "steering_wheel_angle": -0.028, "front_wheel_angle": -0.0012863502684559124, "heading_rate": -5.02480850766809e-05, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059631.0296438}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.028, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059631.0296438}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059631.1297908, "x": -88.23530199022638, "y": 40.09277675318718, "z": 202.31878082201052, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5562218162215617, "steering_wheel_angle": -0.028, "front_wheel_angle": -0.0012863502684559124, "heading_rate": -1.004961701533618e-05, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059631.1296492}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.028, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059631.1296492}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059631.229911, "x": -88.23530199022638, "y": 40.09277675318718, "z": 202.31878082201052, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5577428162215616, "steering_wheel_angle": -0.027, "front_wheel_angle": -0.0012403929219419797, "heading_rate": -2.4226436681407283e-05, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059631.2296596}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059631.2296596}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059631.3300328, "x": -88.23530199022638, "y": 40.09277675318718, "z": 202.31878082201052, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5562218162215617, "steering_wheel_angle": -0.027, "front_wheel_angle": -0.0012403929219419797, "heading_rate": -9.690574672562912e-06, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059631.3296878}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059631.3296878}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059631.4299748, "x": -88.23530199022638, "y": 40.09277675318718, "z": 202.31878082201052, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5557188162215616, "steering_wheel_angle": -0.027, "front_wheel_angle": -0.0012403929219419797, "heading_rate": -4.845287336281456e-06, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059631.4296384}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059631.4296384}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059631.5297875, "x": -88.23530199022638, "y": 40.09277675318718, "z": 202.31878082201052, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.027, "front_wheel_angle": -0.0012403929219419797, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059631.529616}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059631.529616}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059631.6297398, "x": -88.23530190514118, "y": 40.092776978751104, "z": 202.30155024999993, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.047, "front_wheel_angle": -0.0021597690564398976, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059631.6296387}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.047, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059631.6296387}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059631.7299366, "x": -88.23530190514118, "y": 40.092776978751104, "z": 202.30155024999993, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.123, "front_wheel_angle": -0.005657810092800902, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059631.7296574}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.123, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059631.7296574}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059631.8297591, "x": -88.23530190514118, "y": 40.092776978751104, "z": 202.30155024999993, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.278, "front_wheel_angle": -0.012813767064331754, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059631.8296149}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.278, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059631.8296149}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059631.9298954, "x": -88.23530190514118, "y": 40.092776978751104, "z": 202.30155024999993, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.516, "front_wheel_angle": -0.02385927097448736, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059631.929659}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.516, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059631.929659}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059632.0300002, "x": -88.23530190514118, "y": 40.092776978751104, "z": 202.30155024999993, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.887, "front_wheel_angle": -0.0412194029259559, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059632.0296807}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.887, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059632.0296807}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059632.1297097, "x": -88.23530190514118, "y": 40.092776978751104, "z": 202.30155024999993, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -1.303, "front_wheel_angle": -0.06089702210201806, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059632.1296086}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.303, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059632.1296086}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059632.2297046, "x": -88.23530140140251, "y": 40.09277722396277, "z": 202.27617240376998, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -1.655, "front_wheel_angle": -0.07772783697973093, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059632.2296062}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.655, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059632.2296062}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059632.3297772, "x": -88.23530140140251, "y": 40.09277722396277, "z": 202.27617240376998, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5603178162215614, "steering_wheel_angle": -1.773, "front_wheel_angle": -0.08340795732361488, "heading_rate": -0.003265699882995472, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059632.3296614}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.773, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059632.3296614}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059632.4297404, "x": -88.23530140140251, "y": 40.09277722396277, "z": 202.27617240376998, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5722418162215615, "steering_wheel_angle": -1.774, "front_wheel_angle": -0.08345617651693772, "heading_rate": -0.01045630917640686, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059632.4296386}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.32, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.774, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059632.4296386}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059632.5297709, "x": -88.23530140140251, "y": 40.09277722396277, "z": 202.27617240376998, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5597988162215617, "steering_wheel_angle": -1.796, "front_wheel_angle": -0.08451735133944165, "heading_rate": -0.0029784082840012167, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059632.5296311}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.09, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.796, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059632.5296311}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059632.6297574, "x": -88.23530140461929, "y": 40.09277727884932, "z": 202.28498254393918, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5728068162215614, "steering_wheel_angle": -1.977, "front_wheel_angle": -0.09327367969343921, "heading_rate": -0.012058550284904471, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059632.6296506}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.977, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059632.6296506}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059632.7297645, "x": -88.23530140461929, "y": 40.09277727884932, "z": 202.28498254393918, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.561886816221562, "steering_wheel_angle": -2.251, "front_wheel_angle": -0.10661772594867412, "heading_rate": -0.005434790053136831, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059632.729641}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.251, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059632.729641}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059632.8297355, "x": -88.23530140461929, "y": 40.09277727884932, "z": 202.28498254393918, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5768178162215616, "steering_wheel_angle": -2.55, "front_wheel_angle": -0.12130380918708855, "heading_rate": -0.01904723620450608, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059632.8296394}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.55, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059632.8296394}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059632.929774, "x": -88.23530140461929, "y": 40.09277727884932, "z": 202.28498254393918, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5815218162215614, "steering_wheel_angle": -2.834, "front_wheel_angle": -0.13537659591111129, "heading_rate": -0.02553932088996945, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059632.9296415}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.834, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059632.9296415}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059633.0297718, "x": -88.23530140461929, "y": 40.09277727884932, "z": 202.28498254393918, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5869668162215618, "steering_wheel_angle": -3.135, "front_wheel_angle": -0.15042665966484528, "heading_rate": -0.03374837554936459, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059633.0296118}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.135, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059633.0296118}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059633.1297297, "x": -88.23529959283614, "y": 40.09277738638556, "z": 202.29623876975867, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6022788162215615, "steering_wheel_angle": -3.395, "front_wheel_angle": -0.16354142208845918, "heading_rate": -0.05221184262581578, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059633.129634}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.395, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059633.129634}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059633.2297416, "x": -88.23529959283614, "y": 40.09277738638556, "z": 202.29623876975867, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6110538162215615, "steering_wheel_angle": -3.571, "front_wheel_angle": -0.17248087226687514, "heading_rate": -0.06396842810926641, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059633.2296402}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.94, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.571, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059633.2296402}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059633.3296978, "x": -88.23529959283614, "y": 40.09277738638556, "z": 202.29623876975867, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6281418162215617, "steering_wheel_angle": -3.765, "front_wheel_angle": -0.1823935366648274, "heading_rate": -0.08501688194182654, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059633.3296053}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.765, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059633.3296053}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059633.429825, "x": -88.23529959283614, "y": 40.09277738638556, "z": 202.29623876975867, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6417138162215617, "steering_wheel_angle": -3.895, "front_wheel_angle": -0.18907120141503883, "heading_rate": -0.10165833044507057, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059633.4296496}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.895, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059633.4296496}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059633.5297291, "x": -88.23529959283614, "y": 40.09277738638556, "z": 202.29623876975867, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6599988162215618, "steering_wheel_angle": -4.072, "front_wheel_angle": -0.19820920636671366, "heading_rate": -0.12474440045169574, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059633.5296106}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.59, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.072, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059633.5296106}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059633.6298547, "x": -88.23529292812765, "y": 40.09277719296226, "z": 202.2922823682796, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6741938162215617, "steering_wheel_angle": -4.417, "front_wheel_angle": -0.2161767342931811, "heading_rate": -0.15098076170599967, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059633.6296525}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.76, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.417, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059633.6296525}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059633.729764, "x": -88.23529292812765, "y": 40.09277719296226, "z": 202.2922823682796, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.691633816221562, "steering_wheel_angle": -4.888, "front_wheel_angle": -0.2410510144506357, "heading_rate": -0.18821431763999674, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059633.7296436}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.96, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.888, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059633.7296436}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059633.8296988, "x": -88.23529292812765, "y": 40.09277719296226, "z": 202.2922823682796, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7043178162215615, "steering_wheel_angle": -5.31, "front_wheel_angle": -0.2636903527463383, "heading_rate": -0.22146546876616233, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059633.8296044}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.31, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059633.8296044}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059633.9297347, "x": -88.23529292812765, "y": 40.09277719296226, "z": 202.2922823682796, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7328178162215617, "steering_wheel_angle": -5.41, "front_wheel_angle": -0.26910574686516625, "heading_rate": -0.25855839873698083, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059633.9296381}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.41, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059633.9296381}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059634.0296962, "x": -88.23529292812765, "y": 40.09277719296226, "z": 202.2922823682796, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7347818162215614, "steering_wheel_angle": -5.184, "front_wheel_angle": -0.2568948654986019, "heading_rate": -0.24833302492048565, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059634.0296025}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.42, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.184, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059634.0296025}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059634.1297028, "x": -88.2352809008434, "y": 40.09277587499074, "z": 202.30692704312523, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7662468162215617, "steering_wheel_angle": -4.767, "front_wheel_angle": -0.2346219097122963, "heading_rate": -0.254896661959131, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059634.1296031}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.73, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.767, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059634.1296031}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059634.2298007, "x": -88.2352809008434, "y": 40.09277587499074, "z": 202.30692704312523, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7725588162215615, "steering_wheel_angle": -4.301, "front_wheel_angle": -0.21011212904203705, "heading_rate": -0.23241971871167205, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059634.2296174}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.79, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.301, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059634.2296174}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059634.3297708, "x": -88.2352809008434, "y": 40.09277587499074, "z": 202.30692704312523, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.782161816221562, "steering_wheel_angle": -3.787, "front_wheel_angle": -0.1835216057673378, "heading_rate": -0.20881135511417528, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059634.3296466}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.88, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.787, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059634.3296466}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059634.429757, "x": -88.2352809008434, "y": 40.09277587499074, "z": 202.30692704312523, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7875668162215614, "steering_wheel_angle": -3.185, "front_wheel_angle": -0.15294038093506343, "heading_rate": -0.17642274924285814, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059634.4296424}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.185, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059634.4296424}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059634.5297477, "x": -88.2352809008434, "y": 40.09277587499074, "z": 202.30692704312523, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7930218162215614, "steering_wheel_angle": -2.478, "front_wheel_angle": -0.1177553045043234, "heading_rate": -0.13771164085175858, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059634.5296483}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.478, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059634.5296483}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059634.6297624, "x": -88.23526452038395, "y": 40.09277305700323, "z": 202.3005635269625, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8074388162215618, "steering_wheel_angle": -1.757, "front_wheel_angle": -0.08263663954053146, "heading_rate": -0.1006197472579159, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059634.6296084}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.11, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.757, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059634.6296084}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059634.7297416, "x": -88.23526452038395, "y": 40.09277305700323, "z": 202.3005635269625, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8074388162215618, "steering_wheel_angle": -1.042, "front_wheel_angle": -0.048524654809147395, "heading_rate": -0.058996185854335276, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059634.7296352}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.11, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.042, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059634.7296352}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059634.8297968, "x": -88.23526452038395, "y": 40.09277305700323, "z": 202.3005635269625, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8187588162215613, "steering_wheel_angle": -0.345, "front_wheel_angle": -0.015916112610280052, "heading_rate": -0.0199589984615954, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059634.8296072}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.21, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.345, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059634.8296072}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059634.9298053, "x": -88.23526452038395, "y": 40.09277305700323, "z": 202.3005635269625, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.822193816221562, "steering_wheel_angle": 0.32, "front_wheel_angle": 0.01475787342039404, "heading_rate": 0.018679289651601434, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059634.9296548}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.32, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059634.9296548}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059635.0300572, "x": -88.23526452038395, "y": 40.09277305700323, "z": 202.3005635269625, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8176178162215617, "steering_wheel_angle": 0.995, "front_wheel_angle": 0.046306210606236915, "heading_rate": 0.0579241707708007, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059635.0299199}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.995, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059635.0299199}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059635.1297188, "x": -88.23524618371987, "y": 40.09276985936527, "z": 202.3042784429532, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8130738162215616, "steering_wheel_angle": 1.672, "front_wheel_angle": 0.0785449713816035, "heading_rate": 0.0971538220327675, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059635.1296034}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.672, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059635.1296034}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059635.2296984, "x": -88.23524618371987, "y": 40.09276985936527, "z": 202.3042784429532, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8176178162215617, "steering_wheel_angle": 2.347, "front_wheel_angle": 0.11131867069497897, "heading_rate": 0.13972596998742515, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059635.2296033}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.347, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059635.2296033}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059635.32988, "x": -88.23524618371987, "y": 40.09276985936527, "z": 202.3042784429532, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8130738162215616, "steering_wheel_angle": 2.924, "front_wheel_angle": 0.13986189946624047, "heading_rate": 0.17377661435718678, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059635.32962}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.924, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059635.32962}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059635.4298992, "x": -88.23524618371987, "y": 40.09276985936527, "z": 202.3042784429532, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8040818162215615, "steering_wheel_angle": 3.545, "front_wheel_angle": 0.1711570913272038, "heading_rate": 0.20795804548810062, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059635.4296305}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.545, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059635.4296305}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059635.5297518, "x": -88.23524618371987, "y": 40.09276985936527, "z": 202.3042784429532, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8314418162215613, "steering_wheel_angle": 4.192, "front_wheel_angle": 0.20443513557670095, "heading_rate": 0.26888317152188995, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059635.5296364}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.32, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.192, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059635.5296364}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059635.6296985, "x": -88.23522831896727, "y": 40.092768030734604, "z": 202.2955225344753, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8291178162215616, "steering_wheel_angle": 4.802, "front_wheel_angle": 0.23647876638457155, "heading_rate": 0.31064832740131865, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059635.6296027}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.802, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059635.6296027}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059635.729703, "x": -88.23522831896727, "y": 40.092768030734604, "z": 202.2955225344753, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8302788162215617, "steering_wheel_angle": 5.373, "front_wheel_angle": 0.26709975071314035, "heading_rate": 0.35380568963026343, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059635.7296023}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.373, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059635.7296023}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059635.8297553, "x": -88.23522831896727, "y": 40.092768030734604, "z": 202.2955225344753, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8029668162215615, "steering_wheel_angle": 5.931, "front_wheel_angle": 0.29764589871996416, "heading_rate": 0.3678708556654119, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059635.8296058}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.931, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059635.8296058}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059635.929734, "x": -88.23522831896727, "y": 40.092768030734604, "z": 202.2955225344753, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7952178162215615, "steering_wheel_angle": 6.43, "front_wheel_angle": 0.325515787296516, "heading_rate": 0.39553383116673396, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059635.9296076}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.43, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059635.9296076}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059636.0296998, "x": -88.23522831896727, "y": 40.092768030734604, "z": 202.2955225344753, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8007428162215615, "steering_wheel_angle": 6.876, "front_wheel_angle": 0.3508943173954594, "heading_rate": 0.4361050929143197, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059636.029603}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059636.029603}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059636.1298265, "x": -88.23521188895921, "y": 40.09276894904522, "z": 202.3238382121378, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8051988162215613, "steering_wheel_angle": 7.23, "front_wheel_angle": 0.3713696245013601, "heading_rate": 0.4700658492250664, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059636.1296558}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.09, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.23, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059636.1296558}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059636.229748, "x": -88.23521188895921, "y": 40.09276894904522, "z": 202.3238382121378, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8119428162215616, "steering_wheel_angle": 7.483, "front_wheel_angle": 0.386191039734687, "heading_rate": 0.5003200475828729, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059636.2296355}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.483, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059636.2296355}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059636.3297422, "x": -88.23521188895921, "y": 40.09276894904522, "z": 202.3238382121378, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7941188162215616, "steering_wheel_angle": 7.888, "front_wheel_angle": 0.41025754550986926, "heading_rate": 0.5079933332725282, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059636.3296096}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.888, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059636.3296096}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059636.4297562, "x": -88.23521188895921, "y": 40.09276894904522, "z": 202.3238382121378, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7778738162215615, "steering_wheel_angle": 8.328, "front_wheel_angle": 0.43690256505460795, "heading_rate": 0.5180804459981065, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059636.4296465}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.84, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.328, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059636.4296465}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059636.5297167, "x": -88.23521188895921, "y": 40.09276894904522, "z": 202.3238382121378, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7886538162215615, "steering_wheel_angle": 8.775, "front_wheel_angle": 0.4645355982222215, "heading_rate": 0.575494066720794, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059636.5296063}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.94, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.775, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059636.5296063}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059636.6297705, "x": -88.23519753322135, "y": 40.09277249720632, "z": 202.325434732277, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8074388162215618, "steering_wheel_angle": 9.077, "front_wheel_angle": 0.48354533003329203, "heading_rate": 0.637945354771769, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059636.6296432}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.11, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.077, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059636.6296432}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059636.729743, "x": -88.23519753322135, "y": 40.09277249720632, "z": 202.325434732277, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7600068162215616, "steering_wheel_angle": 9.329, "front_wheel_angle": 0.49962840744674014, "heading_rate": 0.5692733019273218, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059636.7296083}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.329, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059636.7296083}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059636.8297272, "x": -88.23519753322135, "y": 40.09277249720632, "z": 202.325434732277, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7832388162215618, "steering_wheel_angle": 9.556, "front_wheel_angle": 0.5142947043204225, "heading_rate": 0.6378441883856244, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059636.8296068}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.556, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059636.8296068}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059636.9299228, "x": -88.23519753322135, "y": 40.09277249720632, "z": 202.325434732277, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7875668162215614, "steering_wheel_angle": 9.744, "front_wheel_angle": 0.5265740135264317, "heading_rate": 0.6653435883774512, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059636.9296124}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.744, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059636.9296124}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059637.029716, "x": -88.23519753322135, "y": 40.09277249720632, "z": 202.325434732277, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7715018162215617, "steering_wheel_angle": 9.876, "front_wheel_angle": 0.5352696456297522, "heading_rate": 0.6439801701348586, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059637.0296032}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.78, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059637.0296032}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059637.1297452, "x": -88.23518642914698, "y": 40.09277841179865, "z": 202.32067018234122, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7768068162215616, "steering_wheel_angle": 10.001, "front_wheel_angle": 0.5435617801259204, "heading_rate": 0.6680144106976122, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059637.1296341}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.001, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059637.1296341}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059637.2297235, "x": -88.23518642914698, "y": 40.09277841179865, "z": 202.32067018234122, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.782161816221562, "steering_wheel_angle": 10.098, "front_wheel_angle": 0.5500358637598812, "heading_rate": 0.68979887915487, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059637.2296128}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.88, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.098, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059637.2296128}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059637.3296952, "x": -88.23518642914698, "y": 40.09277841179865, "z": 202.32067018234122, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7662468162215617, "steering_wheel_angle": 10.161, "front_wheel_angle": 0.5542594103434987, "heading_rate": 0.660085321892849, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059637.3296018}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.73, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059637.3296018}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059637.429866, "x": -88.23518642914698, "y": 40.09277841179865, "z": 202.32067018234122, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7810868162215616, "steering_wheel_angle": 10.163, "front_wheel_angle": 0.5543937349227777, "heading_rate": 0.6941441558515407, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059637.4296594}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059637.4296594}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059637.5297203, "x": -88.23518642914698, "y": 40.09277841179865, "z": 202.32067018234122, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7704468162215616, "steering_wheel_angle": 10.194, "front_wheel_angle": 0.5564776942423175, "heading_rate": 0.673081351385445, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059637.5296056}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.194, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059637.5296056}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059637.6297371, "x": -88.23517819624423, "y": 40.092786384149896, "z": 202.3203138668539, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7843178162215616, "steering_wheel_angle": 10.263, "front_wheel_angle": 0.5611292656426038, "heading_rate": 0.7119996076024357, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059637.6296463}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.9, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.263, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059637.6296463}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059637.729841, "x": -88.23517819624423, "y": 40.092786384149896, "z": 202.3203138668539, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.782161816221562, "steering_wheel_angle": 10.38, "front_wheel_angle": 0.5690584804922979, "heading_rate": 0.7195961457427393, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059637.7296278}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.88, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.38, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059637.7296278}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059637.8297534, "x": -88.23517819624423, "y": 40.092786384149896, "z": 202.3203138668539, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.789742816221562, "steering_wheel_angle": 10.482, "front_wheel_angle": 0.5760147138586825, "heading_rate": 0.7484326300431045, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059637.8296313}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.482, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059637.8296313}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059637.9296887, "x": -88.23517819624423, "y": 40.092786384149896, "z": 202.3203138668539, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7952178162215615, "steering_wheel_angle": 10.533, "front_wheel_angle": 0.5795082939467602, "heading_rate": 0.7669522339086845, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059637.929599}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.533, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059637.929599}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059638.029709, "x": -88.23517819624423, "y": 40.092786384149896, "z": 202.3203138668539, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7996338162215615, "steering_wheel_angle": 10.533, "front_wheel_angle": 0.5795082939467602, "heading_rate": 0.7771782636941337, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059638.0296085}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.04, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.533, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059638.0296085}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059638.1297677, "x": -88.23517313703144, "y": 40.092795868241545, "z": 202.33809042562473, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8074388162215618, "steering_wheel_angle": 10.532, "front_wheel_angle": 0.57943969241229, "heading_rate": 0.7949547842976418, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059638.1296155}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.11, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.532, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059638.1296155}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059638.2299187, "x": -88.23517313703144, "y": 40.092795868241545, "z": 202.33809042562473, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.789742816221562, "steering_wheel_angle": 10.531, "front_wheel_angle": 0.5793710948878287, "heading_rate": 0.7539438979866508, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059638.2296586}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.531, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059638.2296586}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059638.3297627, "x": -88.23517313703144, "y": 40.092795868241545, "z": 202.33809042562473, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8199018162215617, "steering_wheel_angle": 10.531, "front_wheel_angle": 0.5793710948878287, "heading_rate": 0.8229489327176326, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059638.329634}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.531, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059638.329634}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059638.4297988, "x": -88.23517313703144, "y": 40.092795868241545, "z": 202.33809042562473, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7963188162215618, "steering_wheel_angle": 10.531, "front_wheel_angle": 0.5793710948878287, "heading_rate": 0.7692783501490911, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059638.4296694}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.531, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059638.4296694}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059638.5297382, "x": -88.23517313703144, "y": 40.092795868241545, "z": 202.33809042562473, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8164788162215615, "steering_wheel_angle": 10.53, "front_wheel_angle": 0.5793025013726727, "heading_rate": 0.8151596493996202, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059638.5296352}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.19, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.53, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059638.5296352}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059638.6296914, "x": -88.23517260202773, "y": 40.09280644858055, "z": 202.3557705953431, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8085618162215615, "steering_wheel_angle": 10.524, "front_wheel_angle": 0.5788910244378075, "heading_rate": 0.7965562316556093, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059638.6296008}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.524, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059638.6296008}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059638.729802, "x": -88.23517260202773, "y": 40.09280644858055, "z": 202.3557705953431, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8256468162215613, "steering_wheel_angle": 10.521, "front_wheel_angle": 0.5786853400391118, "heading_rate": 0.8344772940635559, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059638.7296748}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.27, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.521, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059638.7296748}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059638.829713, "x": -88.23517260202773, "y": 40.09280644858055, "z": 202.3557705953431, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7963188162215618, "steering_wheel_angle": 10.516, "front_wheel_angle": 0.5783426127443264, "heading_rate": 0.7675525895682163, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059638.8296237}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.516, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059638.8296237}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059638.9297485, "x": -88.23517260202773, "y": 40.09280644858055, "z": 202.3557705953431, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8279588162215616, "steering_wheel_angle": 10.511, "front_wheel_angle": 0.5779999854191387, "heading_rate": 0.8383249944173702, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059638.9296286}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.29, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.511, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059638.9296286}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059639.0298715, "x": -88.23517260202773, "y": 40.09280644858055, "z": 202.3557705953431, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8199018162215617, "steering_wheel_angle": 10.5, "front_wheel_angle": 0.5772465567660482, "heading_rate": 0.8191380369196767, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059639.0296488}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.5, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059639.0296488}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059639.129816, "x": -88.23517609595021, "y": 40.092817190990424, "z": 202.37162249599436, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8142068162215614, "steering_wheel_angle": 10.489, "front_wheel_angle": 0.5764936106140748, "heading_rate": 0.8050913672570168, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059639.1296246}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.17, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.489, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059639.1296246}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059639.229712, "x": -88.23517609595021, "y": 40.092817190990424, "z": 202.37162249599436, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8302788162215617, "steering_wheel_angle": 10.464, "front_wheel_angle": 0.5747841588864341, "heading_rate": 0.8375063511857934, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059639.2296016}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.464, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059639.2296016}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059639.3300498, "x": -88.23517609595021, "y": 40.092817190990424, "z": 202.37162249599436, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8176178162215617, "steering_wheel_angle": 10.456, "front_wheel_angle": 0.57423765792157, "heading_rate": 0.8087044142437682, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059639.329677}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059639.329677}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059639.4297, "x": -88.23517609595021, "y": 40.092817190990424, "z": 202.37162249599436, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8326068162215616, "steering_wheel_angle": 10.42, "front_wheel_angle": 0.571781532573276, "heading_rate": 0.8370330749221933, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059639.429599}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.42, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059639.429599}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059639.5297232, "x": -88.23517609595021, "y": 40.092817190990424, "z": 202.37162249599436, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8233428162215617, "steering_wheel_angle": 10.368, "front_wheel_angle": 0.5682427853329208, "heading_rate": 0.8105857860481841, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059639.5296304}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.25, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.368, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059639.5296304}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059639.629741, "x": -88.23518356219553, "y": 40.09282711880162, "z": 202.44012556896348, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.840817816221562, "steering_wheel_angle": 10.332, "front_wheel_angle": 0.5657990625734672, "heading_rate": 0.8434358481654093, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059639.6296306}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.332, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059639.6296306}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059639.7299345, "x": -88.23518356219553, "y": 40.09282711880162, "z": 202.44012556896348, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8419988162215617, "steering_wheel_angle": 10.296, "front_wheel_angle": 0.563360359723289, "heading_rate": 0.8413650682504981, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059639.7296252}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.296, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059639.7296252}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059639.8297868, "x": -88.23518356219553, "y": 40.09282711880162, "z": 202.44012556896348, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.840817816221562, "steering_wheel_angle": 10.244, "front_wheel_angle": 0.5598465888697741, "heading_rate": 0.8323835425701948, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059639.8296049}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.244, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059639.8296049}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059639.9298532, "x": -88.23518356219553, "y": 40.09282711880162, "z": 202.44012556896348, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8467428162215613, "steering_wheel_angle": 10.157, "front_wheel_angle": 0.5539908063308077, "heading_rate": 0.8336731653723254, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059639.9296393}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.45, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.157, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059639.9296393}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059640.0296955, "x": -88.23518356219553, "y": 40.09282711880162, "z": 202.44012556896348, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8575338162215616, "steering_wheel_angle": 10.068, "front_wheel_angle": 0.5480298543990174, "heading_rate": 0.8440656535200443, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059640.029599}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.54, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.068, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059640.029599}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059640.1298034, "x": -88.23519530588231, "y": 40.09283513059775, "z": 202.4947968677349, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8515188162215614, "steering_wheel_angle": 9.932, "front_wheel_angle": 0.5389775185882125, "heading_rate": 0.8152975350913794, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059640.1296122}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.49, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.932, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059640.1296122}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059640.2296896, "x": -88.23519530588231, "y": 40.09283513059775, "z": 202.4947968677349, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8684868162215613, "steering_wheel_angle": 9.69, "front_wheel_angle": 0.5230344286449021, "heading_rate": 0.8175980184756996, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059640.229596}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.63, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.69, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059640.229596}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059640.329708, "x": -88.23519530588231, "y": 40.09283513059775, "z": 202.4947968677349, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.858742816221562, "steering_wheel_angle": 9.358, "front_wheel_angle": 0.5014924990113082, "heading_rate": 0.7602574646274967, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059640.3296003}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.55, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.358, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059640.3296003}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059640.429752, "x": -88.23519530588231, "y": 40.09283513059775, "z": 202.4947968677349, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8758788162215616, "steering_wheel_angle": 8.976, "front_wheel_angle": 0.47715624672879464, "heading_rate": 0.7452094326608001, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059640.4296415}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.976, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059640.4296415}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059640.5299087, "x": -88.23519530588231, "y": 40.09283513059775, "z": 202.4947968677349, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8758788162215616, "steering_wheel_angle": 8.478, "front_wheel_angle": 0.44611025625178785, "heading_rate": 0.6893765436736311, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059640.529762}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.478, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059640.529762}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059640.6297145, "x": -88.23521092026964, "y": 40.092840605955, "z": 202.49644246551065, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8833428162215613, "steering_wheel_angle": 7.797, "front_wheel_angle": 0.4048125882297901, "heading_rate": 0.6276528619865178, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059640.629602}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.75, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.797, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059640.629602}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059640.7297714, "x": -88.23521092026964, "y": 40.092840605955, "z": 202.49644246551065, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8883588162215617, "steering_wheel_angle": 7.056, "front_wheel_angle": 0.36126784583594107, "heading_rate": 0.5593966222525212, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059640.7296443}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.79, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.056, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059640.7296443}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059640.8300018, "x": -88.23521092026964, "y": 40.092840605955, "z": 202.49644246551065, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9074538162215617, "steering_wheel_angle": 6.414, "front_wheel_angle": 0.3246137250408559, "heading_rate": 0.5179217447402734, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059640.8298478}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.94, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.414, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059640.8298478}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059640.9298189, "x": -88.23521092026964, "y": 40.092840605955, "z": 202.49644246551065, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9256818162215614, "steering_wheel_angle": 5.862, "front_wheel_angle": 0.29383403874533703, "heading_rate": 0.48225767412363973, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059640.9296172}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.862, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059640.9296172}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059641.0298424, "x": -88.23521092026964, "y": 40.092840605955, "z": 202.49644246551065, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.932286816221562, "steering_wheel_angle": 5.321, "front_wheel_angle": 0.26428508180843385, "heading_rate": 0.43657831899183186, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059641.0297477}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.321, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059641.0297477}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059641.129689, "x": -88.23523054397181, "y": 40.09284406214503, "z": 202.49069743760342, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9633138162215618, "steering_wheel_angle": 4.814, "front_wheel_angle": 0.23711592657073932, "heading_rate": 0.41158069651606777, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059641.129596}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.814, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059641.129596}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059641.2297206, "x": -88.23523054397181, "y": 40.09284406214503, "z": 202.49069743760342, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9883338162215614, "steering_wheel_angle": 4.475, "front_wheel_angle": 0.21921802936630508, "heading_rate": 0.39511919945423524, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059641.2296278}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.54, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.475, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059641.2296278}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059641.3297026, "x": -88.23523054397181, "y": 40.09284406214503, "z": 202.49069743760342, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9953988162215617, "steering_wheel_angle": 4.117, "front_wheel_angle": 0.20054100380705522, "heading_rate": 0.36446273149492636, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059641.3295972}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.59, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.117, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059641.3295972}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059641.4298625, "x": -88.23523054397181, "y": 40.09284406214503, "z": 202.49069743760342, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": 3.66, "front_wheel_angle": 0.1770206940415866, "heading_rate": 0.3312319929979417, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059641.4296916}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.66, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059641.4296916}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059641.52988, "x": -88.23523054397181, "y": 40.09284406214503, "z": 202.49069743760342, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": 3.153, "front_wheel_angle": 0.15133114483639823, "heading_rate": 0.306781161710783, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059641.529611}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.153, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059641.529611}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059641.629779, "x": -88.23525558137226, "y": 40.09284595062487, "z": 202.46138073635984, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": 2.58, "front_wheel_angle": 0.12278463250651817, "heading_rate": 0.252113401833224, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059641.6296346}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.58, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059641.6296346}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059641.7300506, "x": -88.23525558137226, "y": 40.09284595062487, "z": 202.46138073635984, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": 1.954, "front_wheel_angle": 0.09215843661332579, "heading_rate": 0.1949489269259343, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059641.7296543}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.954, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059641.7296543}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059641.8297267, "x": -88.23525558137226, "y": 40.09284595062487, "z": 202.46138073635984, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": 1.412, "front_wheel_angle": 0.06609088777146042, "heading_rate": 0.14581886149978832, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059641.829627}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.412, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059641.829627}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059641.9297285, "x": -88.23525558137226, "y": 40.09284595062487, "z": 202.46138073635984, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.183278816221561, "steering_wheel_angle": 1.026, "front_wheel_angle": 0.04776911573848301, "heading_rate": 0.10849603879510666, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059641.9295976}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059641.9295976}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059642.0297172, "x": -88.23525558137226, "y": 40.09284595062487, "z": 202.46138073635984, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.210126816221561, "steering_wheel_angle": 0.959, "front_wheel_angle": 0.04460892511302167, "heading_rate": 0.10409846701798116, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059642.0296242}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.959, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059642.0296242}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059642.129722, "x": -88.23528713087836, "y": 40.09284648727565, "z": 202.4931375029446, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.237486816221562, "steering_wheel_angle": 0.965, "front_wheel_angle": 0.04489168890676057, "heading_rate": 0.10756682016622444, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059642.1296256}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.965, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059642.1296256}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059642.2297568, "x": -88.23528713087836, "y": 40.09284648727565, "z": 202.4931375029446, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.2531018162215615, "steering_wheel_angle": 0.968, "front_wheel_angle": 0.045033088358807635, "heading_rate": 0.10949035659675685, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059642.2296228}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.968, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059642.2296228}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059642.3297741, "x": -88.23528713087836, "y": 40.09284648727565, "z": 202.4931375029446, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": 0.962, "front_wheel_angle": 0.04475030115913386, "heading_rate": 0.1116006478778483, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059642.3296711}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.962, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059642.3296711}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059642.4299705, "x": -88.23528713087836, "y": 40.09284648727565, "z": 202.4931375029446, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": 0.941, "front_wheel_angle": 0.04376091440556099, "heading_rate": 0.11049847696251805, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059642.4297276}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.941, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059642.4297276}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059642.529713, "x": -88.23528713087836, "y": 40.09284648727565, "z": 202.4931375029446, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.324461816221562, "steering_wheel_angle": 0.918, "front_wheel_angle": 0.04267795704956611, "heading_rate": 0.11042958347670932, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059642.5296047}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.918, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059642.5296047}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059642.6296945, "x": -88.23532354661198, "y": 40.09284558647494, "z": 202.47307074601054, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.355758816221561, "steering_wheel_angle": 0.863, "front_wheel_angle": 0.04009105270996293, "heading_rate": 0.10639226035593335, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059642.6295986}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.863, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059642.6295986}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059642.7296956, "x": -88.23532354661198, "y": 40.09284558647494, "z": 202.47307074601054, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": 0.781, "front_wheel_angle": 0.0362414517936151, "heading_rate": 0.09843297802986162, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059642.729597}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.781, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059642.729597}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059642.8296967, "x": -88.23532354661198, "y": 40.09284558647494, "z": 202.47307074601054, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.400926816221562, "steering_wheel_angle": 0.654, "front_wheel_angle": 0.03029624418986007, "heading_rate": 0.08322179042752664, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059642.829596}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.654, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059642.829596}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059642.9297948, "x": -88.23532354661198, "y": 40.09284558647494, "z": 202.47307074601054, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": 0.654, "front_wheel_angle": 0.03029624418986007, "heading_rate": 0.08523426615621504, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059642.929689}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.654, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059642.929689}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059643.0301502, "x": -88.23532354661198, "y": 40.09284558647494, "z": 202.47307074601054, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": 0.489, "front_wheel_angle": 0.022602663974017216, "heading_rate": 0.06358082019438964, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059643.0299664}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.489, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059643.0299664}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059643.1298008, "x": -88.23536356957015, "y": 40.092842802500286, "z": 202.4700028959054, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.464913816221562, "steering_wheel_angle": 0.329, "front_wheel_angle": 0.015174750598687906, "heading_rate": 0.04363075701855528, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059643.1296256}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.329, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059643.1296256}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059643.2297552, "x": -88.23536356957015, "y": 40.092842802500286, "z": 202.4700028959054, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.480753816221561, "steering_wheel_angle": 0.172, "front_wheel_angle": 0.007916843839452169, "heading_rate": 0.02300880811362903, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059643.2296112}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.172, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059643.2296112}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059643.3301318, "x": -88.23536356957015, "y": 40.092842802500286, "z": 202.4700028959054, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.496721816221561, "steering_wheel_angle": 0.081, "front_wheel_angle": 0.0037238174461442725, "heading_rate": 0.010938764310040885, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059643.3296733}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.081, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059643.3296733}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059643.4296925, "x": -88.23536356957015, "y": 40.092842802500286, "z": 202.4700028959054, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.531078816221561, "steering_wheel_angle": 0.074, "front_wheel_angle": 0.0034016931847546217, "heading_rate": 0.01021840683245172, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059643.4295967}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.074, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059643.4295967}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059643.5297449, "x": -88.23536356957015, "y": 40.092842802500286, "z": 202.4700028959054, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.531078816221561, "steering_wheel_angle": 0.087, "front_wheel_angle": 0.0039999711764795165, "heading_rate": 0.012015602499204806, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059643.5295978}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.087, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059643.5295978}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059643.6296976, "x": -88.23540679672007, "y": 40.09283929465388, "z": 202.48694826344268, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.547446816221561, "steering_wheel_angle": 0.086, "front_wheel_angle": 0.003953942526841233, "heading_rate": 0.01200089591186296, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059643.6295946}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.086, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059643.6295946}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059643.7297742, "x": -88.23540679672007, "y": 40.09283929465388, "z": 202.48694826344268, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.563942816221561, "steering_wheel_angle": 0.055, "front_wheel_angle": 0.002527654715902418, "heading_rate": 0.007750832725481388, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059643.7296429}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.055, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059643.7296429}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059643.829761, "x": -88.23540679672007, "y": 40.09283929465388, "z": 202.48694826344268, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": 0.046, "front_wheel_angle": 0.0021137887840879614, "heading_rate": 0.006622113787915718, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059643.8296075}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.046, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059643.8296075}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059643.930131, "x": -88.23540679672007, "y": 40.09283929465388, "z": 202.48694826344268, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": 0.046, "front_wheel_angle": 0.0021137887840879614, "heading_rate": 0.0066881697858001635, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059643.9298606}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.046, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059643.9298606}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059644.029928, "x": -88.23540679672007, "y": 40.09283929465388, "z": 202.48694826344268, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.633341816221561, "steering_wheel_angle": 0.047, "front_wheel_angle": 0.0021597690564398976, "heading_rate": 0.0069011477935290826, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059644.0296683}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.047, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059644.0296683}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059644.1297803, "x": -88.23545265095012, "y": 40.09283564262936, "z": 202.4806890791737, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.650493816221561, "steering_wheel_angle": 0.048, "front_wheel_angle": 0.0022057505363656986, "heading_rate": 0.007117003507199297, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059644.1296341}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.26, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.048, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059644.1296341}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059644.2297719, "x": -88.23545265095012, "y": 40.09283564262936, "z": 202.4806890791737, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.667773816221562, "steering_wheel_angle": 0.05, "front_wheel_angle": 0.002297717119318425, "heading_rate": 0.0074855447261052005, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059644.2296174}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.05, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059644.2296174}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059644.3297484, "x": -88.23545265095012, "y": 40.09283564262936, "z": 202.4806890791737, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.667773816221562, "steering_wheel_angle": 0.052, "front_wheel_angle": 0.002389688533708352, "heading_rate": 0.007785171995591074, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059644.3296192}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.052, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059644.3296192}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059644.429693, "x": -88.23545265095012, "y": 40.09283564262936, "z": 202.4806890791737, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.704918816221562, "steering_wheel_angle": 0.052, "front_wheel_angle": 0.002389688533708352, "heading_rate": 0.007943862551856121, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059644.4295936}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.51, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.052, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059644.4295936}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059644.5297887, "x": -88.23545265095012, "y": 40.09283564262936, "z": 202.4806890791737, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.704918816221562, "steering_wheel_angle": 0.051, "front_wheel_angle": 0.002343702222536118, "heading_rate": 0.007790993137729355, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059644.5296068}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.51, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059644.5296068}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059644.6298404, "x": -88.23550074776671, "y": 40.092831587950066, "z": 202.50721994405464, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.704918816221562, "steering_wheel_angle": 0.06, "front_wheel_angle": 0.0027576225208671363, "heading_rate": 0.009166963725970697, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059644.6296587}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.51, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.06, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059644.6296587}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059644.729864, "x": -88.23550074776671, "y": 40.092831587950066, "z": 202.50721994405464, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.740406816221562, "steering_wheel_angle": 0.065, "front_wheel_angle": 0.002987620546121671, "heading_rate": 0.010118260626235092, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059644.7296956}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.065, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059644.7296956}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059644.8297591, "x": -88.23550074776671, "y": 40.092831587950066, "z": 202.50721994405464, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.758342816221561, "steering_wheel_angle": 0.065, "front_wheel_angle": 0.002987620546121671, "heading_rate": 0.010211624046085012, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059644.829658}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.75, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.065, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059644.829658}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059644.9298465, "x": -88.23550074776671, "y": 40.092831587950066, "z": 202.50721994405464, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.758342816221561, "steering_wheel_angle": 0.065, "front_wheel_angle": 0.002987620546121671, "heading_rate": 0.010211624046085012, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059644.9297206}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.75, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.065, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059644.9297206}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059645.030005, "x": -88.23550074776671, "y": 40.092831587950066, "z": 202.50721994405464, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.758342816221561, "steering_wheel_angle": 0.077, "front_wheel_angle": 0.0035397391768435885, "heading_rate": 0.012098768421172735, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059645.0296378}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.75, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.077, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059645.0296378}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059645.129805, "x": -88.23555071045327, "y": 40.092827070622114, "z": 202.5047770398421, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.796881816221561, "steering_wheel_angle": 0.11, "front_wheel_angle": 0.00505896465535069, "heading_rate": 0.01762748035200401, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059645.1296399}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059645.1296399}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059645.229691, "x": -88.23555071045327, "y": 40.092827070622114, "z": 202.5047770398421, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.776406816221561, "steering_wheel_angle": 0.13, "front_wheel_angle": 0.005980350353755554, "heading_rate": 0.020627782487059314, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059645.2295935}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.13, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059645.2295935}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059645.3297353, "x": -88.23555071045327, "y": 40.092827070622114, "z": 202.5047770398421, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.796881816221561, "steering_wheel_angle": 0.161, "front_wheel_angle": 0.0074094593292757605, "heading_rate": 0.025817807318801872, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059645.3296237}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059645.3296237}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059645.4297714, "x": -88.23555071045327, "y": 40.092827070622114, "z": 202.5047770398421, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.796881816221561, "steering_wheel_angle": 0.226, "front_wheel_angle": 0.010409783299523325, "heading_rate": 0.03627289891423734, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059645.4296327}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.226, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059645.4296327}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059645.5299957, "x": -88.23555071045327, "y": 40.092827070622114, "z": 202.5047770398421, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.815217816221562, "steering_wheel_angle": 0.277, "front_wheel_angle": 0.012767505289246275, "heading_rate": 0.044888199872066346, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059645.5296314}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059645.5296314}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059645.629747, "x": -88.23560218902568, "y": 40.092821827663414, "z": 202.49067234240405, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.833681816221562, "steering_wheel_angle": 0.28, "front_wheel_angle": 0.012906294304269457, "heading_rate": 0.045779554509270244, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059645.6296098}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.28, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059645.6296098}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059645.7297463, "x": -88.23560218902568, "y": 40.092821827663414, "z": 202.49067234240405, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.852273816221562, "steering_wheel_angle": 0.252, "front_wheel_angle": 0.011611360339545783, "heading_rate": 0.04154876598435436, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059645.7296364}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.252, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059645.7296364}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059645.8297203, "x": -88.23560218902568, "y": 40.092821827663414, "z": 202.49067234240405, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.870993816221562, "steering_wheel_angle": 0.199, "front_wheel_angle": 0.00916286808426341, "heading_rate": 0.03307315258373772, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059645.8295984}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.199, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059645.8295984}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059645.929735, "x": -88.23560218902568, "y": 40.092821827663414, "z": 202.49067234240405, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.870993816221562, "steering_wheel_angle": 0.124, "front_wheel_angle": 0.005703883627646137, "heading_rate": 0.020587678237506884, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059645.9296246}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.124, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059645.9296246}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059646.0298362, "x": -88.23560218902568, "y": 40.092821827663414, "z": 202.49067234240405, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": 0.043, "front_wheel_angle": 0.0019758552115223572, "heading_rate": 0.00720107543487969, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059646.0297022}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.043, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059646.0297022}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059646.129732, "x": -88.23565509330342, "y": 40.09281543833354, "z": 202.46633295473788, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": -0.01, "front_wheel_angle": -0.0004593024218401402, "heading_rate": -0.0016739421473079697, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059646.1296012}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.01, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059646.1296012}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059646.2297852, "x": -88.23565509330342, "y": 40.09281543833354, "z": 202.46633295473788, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.911198816221562, "steering_wheel_angle": -0.028, "front_wheel_angle": -0.0012863502684559124, "heading_rate": -0.004728344805715673, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059646.229603}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.028, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059646.229603}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059646.3296883, "x": -88.23565509330342, "y": 40.09281543833354, "z": 202.46633295473788, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.930318816221561, "steering_wheel_angle": -0.017, "front_wheel_angle": -0.0007808857531862971, "heading_rate": -0.002894768478134525, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059646.3295937}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.49, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.017, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059646.3295937}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059646.4303112, "x": -88.23565509330342, "y": 40.09281543833354, "z": 202.46633295473788, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.949566816221562, "steering_wheel_angle": -0.006, "front_wheel_angle": -0.00027556700966073483, "heading_rate": -0.0010301470114087792, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059646.4299977}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.006, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059646.4299977}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059646.530027, "x": -88.23565509330342, "y": 40.09281543833354, "z": 202.46633295473788, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.949566816221562, "steering_wheel_angle": -0.005, "front_wheel_angle": -0.0002296361660609387, "heading_rate": -0.0008584445889968803, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059646.529877}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.005, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059646.529877}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059646.6296918, "x": -88.23570928038355, "y": 40.09280864707971, "z": 202.4350358620414, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.968942816221562, "steering_wheel_angle": -0.005, "front_wheel_angle": -0.0002296361660609387, "heading_rate": -0.0008656207193124236, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059646.6295922}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.005, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059646.6295922}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059646.7296867, "x": -88.23570928038355, "y": 40.09280864707971, "z": 202.4350358620414, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.968942816221562, "steering_wheel_angle": -0.005, "front_wheel_angle": -0.0002296361660609387, "heading_rate": -0.0008656207193124236, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059646.7295938}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.005, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059646.7295938}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059646.829682, "x": -88.23570928038355, "y": 40.09280864707971, "z": 202.4350358620414, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.990893816221561, "steering_wheel_angle": -0.004, "front_wheel_angle": -0.00018370652604977013, "heading_rate": -0.000698945931192681, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059646.8295903}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.004, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059646.8295903}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059646.9298496, "x": -88.23570928038355, "y": 40.09280864707971, "z": 202.4350358620414, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.990893816221561, "steering_wheel_angle": -0.004, "front_wheel_angle": -0.00018370652604977013, "heading_rate": -0.000698945931192681, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059646.9297137}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.004, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059646.9297137}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059647.0300534, "x": -88.23570928038355, "y": 40.09280864707971, "z": 202.4350358620414, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.010541816221561, "steering_wheel_angle": -0.004, "front_wheel_angle": -0.00018370652604977013, "heading_rate": -0.000704686760196317, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059647.0299282}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.004, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059647.0299282}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059647.1298287, "x": -88.2357646213183, "y": 40.092801993366784, "z": 202.42092065797152, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.010541816221561, "steering_wheel_angle": -0.004, "front_wheel_angle": -0.00018370652604977013, "heading_rate": -0.000704686760196317, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059647.1297019}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.004, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059647.1297019}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059647.2296813, "x": -88.2357646213183, "y": 40.092801993366784, "z": 202.42092065797152, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.010541816221561, "steering_wheel_angle": -0.004, "front_wheel_angle": -0.00018370652604977013, "heading_rate": -0.000704686760196317, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059647.2295904}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.004, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059647.2295904}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059647.3298342, "x": -88.2357646213183, "y": 40.092801993366784, "z": 202.42092065797152, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.030317816221562, "steering_wheel_angle": -0.005, "front_wheel_angle": -0.0002296361660609387, "heading_rate": -0.0008880461265484968, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059647.329632}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.9, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.005, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059647.329632}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059647.4296825, "x": -88.2357646213183, "y": 40.092801993366784, "z": 202.42092065797152, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.050221816221562, "steering_wheel_angle": -0.006, "front_wheel_angle": -0.00027556700966073483, "heading_rate": -0.0010742807914168881, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059647.4295917}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.006, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059647.4295917}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059647.5298183, "x": -88.2357646213183, "y": 40.092801993366784, "z": 202.42092065797152, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.070253816221562, "steering_wheel_angle": -0.01, "front_wheel_angle": -0.0004593024218401402, "heading_rate": -0.0018049151127457852, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059647.529723}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.01, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059647.529723}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059647.6297057, "x": -88.23582135113912, "y": 40.09279487921425, "z": 202.44865703000946, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.050221816221562, "steering_wheel_angle": -0.064, "front_wheel_angle": -0.0029416185228755055, "heading_rate": -0.011467749037559295, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059647.6295905}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.064, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059647.6295905}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059647.729717, "x": -88.23582135113912, "y": 40.09279487921425, "z": 202.44865703000946, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.090413816221561, "steering_wheel_angle": -0.142, "front_wheel_angle": -0.006533415102241901, "heading_rate": -0.025878817099444482, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059647.729617}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.14, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.142, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059647.729617}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059647.829943, "x": -88.23582135113912, "y": 40.09279487921425, "z": 202.44865703000946, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.070253816221562, "steering_wheel_angle": -0.165, "front_wheel_angle": -0.007593945721736128, "heading_rate": -0.029842407231352747, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059647.8297899}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.165, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059647.8297899}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059647.9299796, "x": -88.23582135113912, "y": 40.09279487921425, "z": 202.44865703000946, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.090413816221561, "steering_wheel_angle": -0.166, "front_wheel_angle": -0.007640070366829615, "heading_rate": -0.030262430033730345, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059647.9297504}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.14, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059647.9297504}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059648.0299761, "x": -88.23582135113912, "y": 40.09279487921425, "z": 202.44865703000946, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.113246816221562, "steering_wheel_angle": -0.164, "front_wheel_angle": -0.007547822295530698, "heading_rate": -0.030162378283213446, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059648.029662}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.164, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059648.029662}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059648.1299503, "x": -88.2358792708344, "y": 40.09278776708464, "z": 202.45705567282226, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.113246816221562, "steering_wheel_angle": -0.175, "front_wheel_angle": -0.00805524703858198, "heading_rate": -0.03219021859088526, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059648.129825}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.175, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059648.129825}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059648.2297196, "x": -88.2358792708344, "y": 40.09278776708464, "z": 202.45705567282226, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.050221816221562, "steering_wheel_angle": -0.233, "front_wheel_angle": -0.010733203289347445, "heading_rate": -0.041844329055946206, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059648.2295969}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.233, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059648.2295969}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059648.3296926, "x": -88.2358792708344, "y": 40.09278776708464, "z": 202.45705567282226, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.113246816221562, "steering_wheel_angle": -0.289, "front_wheel_angle": -0.013322727784568422, "heading_rate": -0.05324201933555666, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059648.3295984}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059648.3295984}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059648.4297285, "x": -88.2358792708344, "y": 40.09278776708464, "z": 202.45705567282226, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.070253816221562, "steering_wheel_angle": -0.278, "front_wheel_angle": -0.012813767064331754, "heading_rate": -0.05035685636561942, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059648.4296174}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.278, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059648.4296174}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059648.5298674, "x": -88.2358792708344, "y": 40.09278776708464, "z": 202.45705567282226, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.070253816221562, "steering_wheel_angle": -0.239, "front_wheel_angle": -0.011010468216273371, "heading_rate": -0.043269447857074865, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059648.5297444}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.239, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059648.5297444}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059648.6303086, "x": -88.23593789965366, "y": 40.09278137399101, "z": 202.4389116751095, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.050221816221562, "steering_wheel_angle": -0.214, "front_wheel_angle": -0.009855488640690276, "heading_rate": -0.03842225049854948, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059648.629684}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.214, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059648.629684}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059648.7297585, "x": -88.23593789965366, "y": 40.09278137399101, "z": 202.4389116751095, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.030317816221562, "steering_wheel_angle": -0.206, "front_wheel_angle": -0.009486056769587978, "heading_rate": -0.03668546055397042, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059648.7295942}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.9, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.206, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059648.7295942}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059648.829681, "x": -88.23593789965366, "y": 40.09278137399101, "z": 202.4389116751095, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.990893816221561, "steering_wheel_angle": -0.206, "front_wheel_angle": -0.009486056769587978, "heading_rate": -0.03609256422178504, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059648.8295896}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.206, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059648.8295896}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059648.9304502, "x": -88.23593789965366, "y": 40.09278137399101, "z": 202.4389116751095, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": -0.202, "front_wheel_angle": -0.009301370185803915, "heading_rate": -0.03390011194385455, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059648.9299893}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.202, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059648.9299893}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059649.0297668, "x": -88.23593789965366, "y": 40.09278137399101, "z": 202.4389116751095, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.833681816221562, "steering_wheel_angle": -0.203, "front_wheel_angle": -0.009347539997798858, "heading_rate": -0.03315552160650687, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059649.0296044}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.203, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059649.0296044}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059649.129718, "x": -88.2359936889921, "y": 40.09277640004053, "z": 202.44178155026384, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.740406816221562, "steering_wheel_angle": -0.209, "front_wheel_angle": -0.009624584547123486, "heading_rate": -0.032596767460993985, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059649.1295917}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.209, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059649.1295917}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059649.2297912, "x": -88.2359936889921, "y": 40.09277640004053, "z": 202.44178155026384, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.667773816221562, "steering_wheel_angle": -0.214, "front_wheel_angle": -0.009855488640690276, "heading_rate": -0.032108373663116495, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059649.229701}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.214, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059649.229701}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059649.3299346, "x": -88.2359936889921, "y": 40.09277640004053, "z": 202.44178155026384, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.547446816221561, "steering_wheel_angle": -0.215, "front_wheel_angle": -0.009901673129929588, "heading_rate": -0.030054107291773255, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059649.3296368}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.215, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059649.3296368}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059649.4300742, "x": -88.2359936889921, "y": 40.09277640004053, "z": 202.44178155026384, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.480753816221561, "steering_wheel_angle": -0.214, "front_wheel_angle": -0.009855488640690276, "heading_rate": -0.028643441253427666, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059649.429909}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.214, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059649.429909}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059649.5298147, "x": -88.2359936889921, "y": 40.09277640004053, "z": 202.44178155026384, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": -0.217, "front_wheel_angle": -0.009994045779712853, "heading_rate": -0.026820851761657966, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059649.5296392}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.217, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059649.5296392}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059649.630252, "x": -88.23603998939855, "y": 40.092773144463436, "z": 202.45369660403455, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3099338162215615, "steering_wheel_angle": -0.224, "front_wheel_angle": -0.010317388612864353, "heading_rate": -0.026358639007827485, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059649.6297164}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.54, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.224, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059649.6297164}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059649.7297575, "x": -88.23603998939855, "y": 40.092773144463436, "z": 202.45369660403455, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1966388162215615, "steering_wheel_angle": -0.228, "front_wheel_angle": -0.01050218288540799, "heading_rate": -0.02416411387380581, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059649.7296152}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.228, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059649.7296152}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059649.8297346, "x": -88.23603998939855, "y": 40.092773144463436, "z": 202.45369660403455, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.142353816221561, "steering_wheel_angle": -0.229, "front_wheel_angle": -0.010548384515803491, "heading_rate": -0.022910622369450132, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059649.8296025}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059649.8296025}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059649.929773, "x": -88.23603998939855, "y": 40.092773144463436, "z": 202.45369660403455, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": -0.231, "front_wheel_angle": -0.010640791451987907, "heading_rate": -0.02074201306708207, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059649.9296324}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.231, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059649.9296324}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059650.0297327, "x": -88.23603998939855, "y": 40.092773144463436, "z": 202.45369660403455, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": -0.235, "front_wheel_angle": -0.01082562002866119, "heading_rate": -0.019030153619357865, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059650.0295997}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.235, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059650.0295997}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059650.130047, "x": -88.23607260219369, "y": 40.09277126374108, "z": 202.45821044062012, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9126218162215616, "steering_wheel_angle": -0.241, "front_wheel_angle": -0.011102899666132838, "heading_rate": -0.01726224866152657, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059650.1296597}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.241, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059650.1296597}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059650.229968, "x": -88.23607260219369, "y": 40.09277126374108, "z": 202.45821044062012, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8551218162215615, "steering_wheel_angle": -0.243, "front_wheel_angle": -0.011195336021068862, "heading_rate": -0.015394230182438892, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059650.229682}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.243, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059650.229682}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059650.3299983, "x": -88.23607260219369, "y": 40.09277126374108, "z": 202.45821044062012, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7941188162215616, "steering_wheel_angle": -0.244, "front_wheel_angle": -0.011241556038184296, "heading_rate": -0.013130339263592066, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059650.329636}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.244, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059650.329636}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059650.429912, "x": -88.23607260219369, "y": 40.09277126374108, "z": 202.45821044062012, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7397268162215616, "steering_wheel_angle": -0.246, "front_wheel_angle": -0.011333999752199377, "heading_rate": -0.010936007105606743, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059650.429609}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.47, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.246, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059650.429609}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059650.5297868, "x": -88.23607260219369, "y": 40.09277126374108, "z": 202.45821044062012, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.697021816221562, "steering_wheel_angle": -0.248, "front_wheel_angle": -0.011426448373243307, "heading_rate": -0.009016574335430919, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059650.5296025}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.248, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059650.5296025}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059650.629774, "x": -88.23609080082451, "y": 40.09277039611112, "z": 202.45009669947797, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.656742816221562, "steering_wheel_angle": -0.25, "front_wheel_angle": -0.011518901902098604, "heading_rate": -0.006974643615862593, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059650.629605}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.55, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.25, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059650.629605}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059650.72984, "x": -88.23609080082451, "y": 40.09277039611112, "z": 202.45009669947797, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6230388162215617, "steering_wheel_angle": -0.251, "front_wheel_angle": -0.011565130507199158, "heading_rate": -0.005014791887738336, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059650.7296038}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.11, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.251, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059650.7296038}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059650.8297899, "x": -88.23609080082451, "y": 40.09277039611112, "z": 202.45009669947797, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5964018162215616, "steering_wheel_angle": -0.25, "front_wheel_angle": -0.011518901902098604, "heading_rate": -0.0032398344538200428, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059650.829643}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.25, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059650.829643}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059650.9299746, "x": -88.23609080082451, "y": 40.09277039611112, "z": 202.45009669947797, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.571678816221562, "steering_wheel_angle": -0.25, "front_wheel_angle": -0.011518901902098604, "heading_rate": -0.0013949287231725185, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059650.92967}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.25, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059650.92967}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059651.0302172, "x": -88.23609080082451, "y": 40.09277039611112, "z": 202.45009669947797, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5577428162215616, "steering_wheel_angle": -0.249, "front_wheel_angle": -0.011472674524145734, "heading_rate": -0.0002240855059329556, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059651.029693}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.249, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059651.029693}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059651.1298647, "x": -88.23609567693215, "y": 40.09277015622319, "z": 202.4412213214998, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5597988162215617, "steering_wheel_angle": -0.247, "front_wheel_angle": -0.011380223449293793, "heading_rate": -0.00040010325317722204, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059651.1296072}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.09, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.247, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059651.1296072}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059651.2298167, "x": -88.23609567693215, "y": 40.09277015622319, "z": 202.4412213214998, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5577428162215616, "steering_wheel_angle": -0.234, "front_wheel_angle": -0.010779411046211277, "heading_rate": -0.0002105435268104863, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059651.2296195}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.234, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059651.2296195}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059651.3297954, "x": -88.23609567693215, "y": 40.09277015622319, "z": 202.4412213214998, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5562218162215617, "steering_wheel_angle": -0.232, "front_wheel_angle": -0.010686996757971879, "heading_rate": -8.34953409163596e-05, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059651.3296335}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.232, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059651.3296335}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059651.4297762, "x": -88.23609567693215, "y": 40.09277015622319, "z": 202.4412213214998, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5557188162215616, "steering_wheel_angle": -0.233, "front_wheel_angle": -0.010733203289347445, "heading_rate": -4.1928185426799806e-05, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059651.4296315}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.233, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059651.4296315}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059651.529758, "x": -88.23609567693215, "y": 40.09277015622319, "z": 202.4412213214998, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.232, "front_wheel_angle": -0.010686996757971879, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059651.5296013}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.232, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059651.5296013}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059651.629782, "x": -88.23609550618507, "y": 40.09277000262309, "z": 202.42694268510033, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.233, "front_wheel_angle": -0.010733203289347445, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059651.629604}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.233, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059651.629604}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059651.7297313, "x": -88.23609550618507, "y": 40.09277000262309, "z": 202.42694268510033, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.233, "front_wheel_angle": -0.010733203289347445, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059651.729605}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.233, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059651.729605}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059651.8304334, "x": -88.23609550618507, "y": 40.09277000262309, "z": 202.42694268510033, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.233, "front_wheel_angle": -0.010733203289347445, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059651.8296843}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.233, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059651.8296843}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059651.9298425, "x": -88.23609550618507, "y": 40.09277000262309, "z": 202.42694268510033, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.24, "front_wheel_angle": -0.011056683328117477, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059651.9296103}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.24, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059651.9296103}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059652.0298035, "x": -88.23609550618507, "y": 40.09277000262309, "z": 202.42694268510033, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.269, "front_wheel_angle": -0.012397455352819551, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059652.029612}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.269, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059652.029612}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059652.1297657, "x": -88.23609550618507, "y": 40.09277000262309, "z": 202.42694268510033, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.335, "front_wheel_angle": -0.015452724284021082, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059652.129601}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059652.129601}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059652.2297382, "x": -88.23609599390794, "y": 40.09276988345957, "z": 202.44222431245154, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.464, "front_wheel_angle": -0.02143995209022835, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059652.229598}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.464, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059652.229598}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059652.3297355, "x": -88.23609599390794, "y": 40.09276988345957, "z": 202.44222431245154, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.657, "front_wheel_angle": -0.030436445534596065, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059652.3295958}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.657, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059652.3295958}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059652.4296408, "x": -88.23609599390794, "y": 40.09276988345957, "z": 202.44222431245154, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.974, "front_wheel_angle": -0.045315922387792515, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059652.4295146}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.974, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059652.4295146}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059652.5298367, "x": -88.23609599390794, "y": 40.09276988345957, "z": 202.44222431245154, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -1.402, "front_wheel_angle": -0.06561372025590478, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059652.52963}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.402, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059652.52963}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059652.6297946, "x": -88.23609601895278, "y": 40.092769836882695, "z": 202.4452589535818, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -1.891, "front_wheel_angle": -0.0891074683563317, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059652.6296334}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.891, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059652.6296334}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059652.7298124, "x": -88.23609601895278, "y": 40.092769836882695, "z": 202.4452589535818, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -2.319, "front_wheel_angle": -0.1099461724365061, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059652.7296276}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.319, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059652.7296276}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059652.829749, "x": -88.23609601895278, "y": 40.092769836882695, "z": 202.4452589535818, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -2.714, "front_wheel_angle": -0.1294154663240987, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059652.8296003}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.714, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059652.8296003}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059652.9297597, "x": -88.23609601895278, "y": 40.092769836882695, "z": 202.4452589535818, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5634738162215616, "steering_wheel_angle": -3.062, "front_wheel_angle": -0.14676369121710048, "heading_rate": -0.009239162046664556, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059652.9296026}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.062, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059652.9296026}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059653.0297577, "x": -88.23609601895278, "y": 40.092769836882695, "z": 202.4452589535818, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5597988162215617, "steering_wheel_angle": -3.351, "front_wheel_angle": -0.16131440448198744, "heading_rate": -0.005720919735755567, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059653.0295994}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.09, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.351, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059653.0295994}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059653.1297534, "x": -88.23609607419326, "y": 40.09276974196737, "z": 202.4452962027786, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5634738162215616, "steering_wheel_angle": -3.585, "front_wheel_angle": -0.1731941368465159, "heading_rate": -0.0109341807986768, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059653.129596}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.585, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059653.129596}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059653.229774, "x": -88.23609607419326, "y": 40.09276974196737, "z": 202.4452962027786, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5572338162215615, "steering_wheel_angle": -3.806, "front_wheel_angle": -0.18449650017636565, "heading_rate": -0.002915918076135692, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059653.2296262}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.04, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.806, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059653.2296262}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059653.329734, "x": -88.23609607419326, "y": 40.09276974196737, "z": 202.4452962027786, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5650788162215616, "steering_wheel_angle": -4.013, "front_wheel_angle": -0.19515724886475974, "heading_rate": -0.014671057390390168, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059653.329599}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.19, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059653.329599}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059653.429794, "x": -88.23609607419326, "y": 40.09276974196737, "z": 202.4452962027786, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5661588162215616, "steering_wheel_angle": -4.214, "front_wheel_angle": -0.20557927315008576, "heading_rate": -0.017105583281796725, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059653.4296331}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.21, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.214, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059653.4296331}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059653.5298111, "x": -88.23609607419326, "y": 40.09276974196737, "z": 202.4452962027786, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5705588162215616, "steering_wheel_angle": -4.493, "front_wheel_angle": -0.2201631065134574, "heading_rate": -0.025351289161262766, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059653.529609}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.29, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.493, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059653.529609}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059653.629697, "x": -88.23609692105725, "y": 40.092769699698835, "z": 202.4447370972107, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5750868162215617, "steering_wheel_angle": -4.836, "front_wheel_angle": -0.23828474969505137, "heading_rate": -0.0351065674153112, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059653.629536}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.37, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.836, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059653.629536}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059653.7298493, "x": -88.23609692105725, "y": 40.092769699698835, "z": 202.4447370972107, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5815218162215614, "steering_wheel_angle": -5.265, "front_wheel_angle": -0.2612598393078204, "heading_rate": -0.05013206055686103, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059653.7295957}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.265, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059653.7295957}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059653.829758, "x": -88.23609692105725, "y": 40.092769699698835, "z": 202.4447370972107, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5875818162215616, "steering_wheel_angle": -5.829, "front_wheel_angle": -0.29201449104694277, "heading_rate": -0.06810649797128736, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059653.8295937}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.829, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059653.8295937}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059653.9297523, "x": -88.23609692105725, "y": 40.092769699698835, "z": 202.4447370972107, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5964018162215616, "steering_wheel_angle": -6.321, "front_wheel_angle": -0.31938172605495985, "heading_rate": -0.09301032381500055, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059653.9296036}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.321, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059653.9296036}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059654.0297527, "x": -88.23609692105725, "y": 40.092769699698835, "z": 202.4447370972107, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6076388162215616, "steering_wheel_angle": -6.719, "front_wheel_angle": -0.34190856120623014, "heading_rate": -0.12372589151812174, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059654.029598}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.719, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059654.029598}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059654.130079, "x": -88.23610048045947, "y": 40.09276970504358, "z": 202.43499767024446, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6117428162215615, "steering_wheel_angle": -7.096, "front_wheel_angle": -0.3635835923923473, "heading_rate": -0.1412010634730789, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059654.1296926}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.096, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059654.1296926}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059654.2298536, "x": -88.23610048045947, "y": 40.09276970504358, "z": 202.43499767024446, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6252138162215615, "steering_wheel_angle": -7.549, "front_wheel_angle": -0.3900840038787877, "heading_rate": -0.18309162207275473, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059654.229658}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.14, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.549, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059654.229658}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059654.330231, "x": -88.23610048045947, "y": 40.09276970504358, "z": 202.43499767024446, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6356018162215618, "steering_wheel_angle": -7.92, "front_wheel_angle": -0.41217751068729686, "heading_rate": -0.21861125646541602, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059654.3296654}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.92, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059654.3296654}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059654.4298182, "x": -88.23610048045947, "y": 40.09276970504358, "z": 202.43499767024446, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6455988162215616, "steering_wheel_angle": -8.417, "front_wheel_angle": -0.44235799087128125, "heading_rate": -0.2608854353196563, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059654.4296103}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.417, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059654.4296103}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059654.5298054, "x": -88.23610048045947, "y": 40.09276970504358, "z": 202.43499767024446, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6599988162215618, "steering_wheel_angle": -8.919, "front_wheel_angle": -0.47356461036026837, "heading_rate": -0.31828473128596346, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059654.5296295}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.59, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.919, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059654.5296295}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059654.6297374, "x": -88.23610782535229, "y": 40.092770594513674, "z": 202.424761488136, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6716468162215614, "steering_wheel_angle": -9.344, "front_wheel_angle": -0.5005922463290741, "heading_rate": -0.3697008235812153, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059654.6296008}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.73, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.344, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059654.6296008}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059654.729755, "x": -88.23610782535229, "y": 40.092770594513674, "z": 202.424761488136, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.682813816221562, "steering_wheel_angle": -9.653, "front_wheel_angle": -0.5206150268842986, "heading_rate": -0.41659551066346984, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059654.7296257}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.86, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.653, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059654.7296257}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059654.8298213, "x": -88.23610782535229, "y": 40.092770594513674, "z": 202.424761488136, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6961188162215617, "steering_wheel_angle": -9.989, "front_wheel_angle": -0.5427632698525117, "heading_rate": -0.4735999854689088, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059654.82963}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.989, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059654.82963}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059654.9297502, "x": -88.23610782535229, "y": 40.092770594513674, "z": 202.424761488136, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7108068162215617, "steering_wheel_angle": -10.364, "front_wheel_angle": -0.5679710117200418, "heading_rate": -0.5408976640145563, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059654.929598}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.17, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.364, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059654.929598}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059655.0298243, "x": -88.23610782535229, "y": 40.092770594513674, "z": 202.424761488136, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7202468162215614, "steering_wheel_angle": -10.635, "front_wheel_angle": -0.5865268440697153, "heading_rate": -0.5892575134560765, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059655.0296464}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.27, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.635, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059655.0296464}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059655.130826, "x": -88.23611879077932, "y": 40.09277361722587, "z": 202.47025117753364, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.728913816221562, "steering_wheel_angle": -10.904, "front_wheel_angle": -0.6052423805024998, "heading_rate": -0.6378090104463454, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059655.1297276}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.904, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059655.1297276}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059655.2299855, "x": -88.23611879077932, "y": 40.09277361722587, "z": 202.47025117753364, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7517988162215614, "steering_wheel_angle": -11.122, "front_wheel_angle": -0.6206365183963597, "heading_rate": -0.7232477610695641, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059655.2296684}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.59, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.122, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059655.2296684}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059655.3297715, "x": -88.23611879077932, "y": 40.09277361722587, "z": 202.47025117753364, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7538388162215615, "steering_wheel_angle": -11.233, "front_wheel_angle": -0.6285557912808464, "heading_rate": -0.7411024574801323, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059655.3296044}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.233, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059655.3296044}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059655.4297698, "x": -88.23611879077932, "y": 40.09277361722587, "z": 202.47025117753364, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7652018162215617, "steering_wheel_angle": -11.298, "front_wheel_angle": -0.6332192044167816, "heading_rate": -0.7799354632703831, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059655.4295962}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.298, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059655.4295962}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059655.5297542, "x": -88.23611879077932, "y": 40.09277361722587, "z": 202.47025117753364, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7832388162215618, "steering_wheel_angle": -11.353, "front_wheel_angle": -0.6371803926130795, "heading_rate": -0.8355829318044061, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059655.5295959}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.353, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059655.5295959}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059655.6300569, "x": -88.23613146503732, "y": 40.092780207681, "z": 202.47859878179048, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.782161816221562, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -0.834452663663666, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059655.6296763}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.88, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059655.6296763}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059655.7297432, "x": -88.23613146503732, "y": 40.092780207681, "z": 202.47859878179048, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8051988162215613, "steering_wheel_angle": -11.383, "front_wheel_angle": -0.639346979450613, "heading_rate": -0.8974630953060238, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059655.7296102}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.09, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.383, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059655.7296102}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059655.8298688, "x": -88.23613146503732, "y": 40.092780207681, "z": 202.47859878179048, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7810868162215616, "steering_wheel_angle": -11.387, "front_wheel_angle": -0.6396361762549642, "heading_rate": -0.8340696100923013, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059655.8295946}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.387, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059655.8295946}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059655.9299376, "x": -88.23613146503732, "y": 40.092780207681, "z": 202.47859878179048, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7963188162215618, "steering_wheel_angle": -11.388, "front_wheel_angle": -0.6397084871944011, "heading_rate": -0.874888021417789, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059655.9296184}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.388, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059655.9296184}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059656.0297542, "x": -88.23613146503732, "y": 40.092780207681, "z": 202.47859878179048, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.789742816221562, "steering_wheel_angle": -11.389, "front_wheel_angle": -0.6397808028310075, "heading_rate": -0.8575778713071469, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059656.0295987}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.389, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059656.0295987}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059656.1297238, "x": -88.23614250533807, "y": 40.09279063855414, "z": 202.50058768312394, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7810868162215616, "steering_wheel_angle": -11.389, "front_wheel_angle": -0.6397808028310075, "heading_rate": -0.8343215222547496, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059656.1295924}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.389, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059656.1295924}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059656.2298453, "x": -88.23614250533807, "y": 40.09279063855414, "z": 202.50058768312394, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7800138162215617, "steering_wheel_angle": -11.389, "front_wheel_angle": -0.6397808028310075, "heading_rate": -0.8314144786232001, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059656.2296078}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.86, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.389, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059656.2296078}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059656.3298116, "x": -88.23614250533807, "y": 40.09279063855414, "z": 202.50058768312394, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7715018162215617, "steering_wheel_angle": -11.389, "front_wheel_angle": -0.6397808028310075, "heading_rate": -0.8081581295708028, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059656.3296185}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.78, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.389, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059656.3296185}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059656.429732, "x": -88.23614250533807, "y": 40.09279063855414, "z": 202.50058768312394, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7843178162215616, "steering_wheel_angle": -11.389, "front_wheel_angle": -0.6397808028310075, "heading_rate": -0.8430426531493985, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059656.4296203}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.9, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.389, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059656.4296203}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059656.529706, "x": -88.23614250533807, "y": 40.09279063855414, "z": 202.50058768312394, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7768068162215616, "steering_wheel_angle": -11.389, "front_wheel_angle": -0.6397808028310075, "heading_rate": -0.822693347728551, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059656.5295894}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.389, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059656.5295894}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059656.6301117, "x": -88.23614891532705, "y": 40.09280277826899, "z": 202.5269912804216, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7672938162215615, "steering_wheel_angle": -11.389, "front_wheel_angle": -0.6397808028310075, "heading_rate": -0.7965299550446043, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059656.6296494}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.389, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059656.6296494}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059656.7297654, "x": -88.23614891532705, "y": 40.09280277826899, "z": 202.5269912804216, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7600068162215616, "steering_wheel_angle": -11.389, "front_wheel_angle": -0.6397808028310075, "heading_rate": -0.7761806496237567, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059656.7296078}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.389, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059656.7296078}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059656.829788, "x": -88.23614891532705, "y": 40.09280277826899, "z": 202.5269912804216, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7528178162215617, "steering_wheel_angle": -11.389, "front_wheel_angle": -0.6397808028310075, "heading_rate": -0.7558313442029092, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059656.8296006}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.6, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.389, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059656.8296006}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059656.929768, "x": -88.23614891532705, "y": 40.09280277826899, "z": 202.5269912804216, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7467338162215618, "steering_wheel_angle": -11.389, "front_wheel_angle": -0.6397808028310075, "heading_rate": -0.7383890824136112, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059656.9296339}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.54, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.389, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059656.9296339}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059657.0297792, "x": -88.23614891532705, "y": 40.09280277826899, "z": 202.5269912804216, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7538388162215615, "steering_wheel_angle": -11.389, "front_wheel_angle": -0.6397808028310075, "heading_rate": -0.7587383878344588, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059657.0296235}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.389, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059657.0296235}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059657.1297886, "x": -88.23615015062593, "y": 40.09281507000822, "z": 202.46936181423607, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7579428162215613, "steering_wheel_angle": -11.389, "front_wheel_angle": -0.6397808028310075, "heading_rate": -0.7703665623606574, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059657.1296422}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.389, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059657.1296422}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059657.2298493, "x": -88.23615015062593, "y": 40.09281507000822, "z": 202.46936181423607, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7641588162215616, "steering_wheel_angle": -11.389, "front_wheel_angle": -0.6397808028310075, "heading_rate": -0.7878088241499553, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059657.2296488}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.71, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.389, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059657.2296488}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059657.3299618, "x": -88.23615015062593, "y": 40.09281507000822, "z": 202.46936181423607, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.728913816221562, "steering_wheel_angle": -11.389, "front_wheel_angle": -0.6397808028310075, "heading_rate": -0.6860622970457175, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059657.3296976}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.389, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059657.3296976}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059657.4299023, "x": -88.23615015062593, "y": 40.09281507000822, "z": 202.46936181423607, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7497668162215616, "steering_wheel_angle": -11.389, "front_wheel_angle": -0.6397808028310075, "heading_rate": -0.7471102133082601, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059657.429643}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.389, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059657.429643}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059657.5303054, "x": -88.23615015062593, "y": 40.09281507000822, "z": 202.46936181423607, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7318388162215617, "steering_wheel_angle": -11.389, "front_wheel_angle": -0.6397808028310075, "heading_rate": -0.6947834279403665, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059657.5296638}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.39, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.389, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059657.5296638}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059657.6297567, "x": -88.23614742744559, "y": 40.09282657753262, "z": 202.4420811945686, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7447218162215616, "steering_wheel_angle": -11.389, "front_wheel_angle": -0.6397808028310075, "heading_rate": -0.7325749951505118, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059657.6295943}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.389, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059657.6295943}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059657.7297843, "x": -88.23614742744559, "y": 40.09282657753262, "z": 202.4420811945686, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7347818162215614, "steering_wheel_angle": -11.389, "front_wheel_angle": -0.6397808028310075, "heading_rate": -0.7035045588350153, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059657.7296119}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.42, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.389, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059657.7296119}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059657.8297687, "x": -88.23614742744559, "y": 40.09282657753262, "z": 202.4420811945686, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7507818162215614, "steering_wheel_angle": -11.389, "front_wheel_angle": -0.6397808028310075, "heading_rate": -0.7500172569398098, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059657.8296468}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.389, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059657.8296468}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059657.9297073, "x": -88.23614742744559, "y": 40.09282657753262, "z": 202.4420811945686, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7387338162215618, "steering_wheel_angle": -11.389, "front_wheel_angle": -0.6397808028310075, "heading_rate": -0.715132733361214, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059657.9295886}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.389, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059657.9295886}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059658.029696, "x": -88.23614742744559, "y": 40.09282657753262, "z": 202.4420811945686, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7487538162215617, "steering_wheel_angle": -11.389, "front_wheel_angle": -0.6397808028310075, "heading_rate": -0.7442031696767105, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059658.0295868}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.389, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059658.0295868}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059658.12972, "x": -88.2361412672578, "y": 40.092836811141716, "z": 202.45549630760502, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7487538162215617, "steering_wheel_angle": -11.388, "front_wheel_angle": -0.6397084871944011, "heading_rate": -0.7440908089134683, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059658.1296122}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.388, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059658.1296122}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059658.2297297, "x": -88.2361412672578, "y": 40.092836811141716, "z": 202.45549630760502, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7538388162215615, "steering_wheel_angle": -11.388, "front_wheel_angle": -0.6397084871944011, "heading_rate": -0.7586238325250595, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059658.2296147}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.388, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059658.2296147}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059658.3297527, "x": -88.2361412672578, "y": 40.092836811141716, "z": 202.45549630760502, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7579428162215613, "steering_wheel_angle": -11.388, "front_wheel_angle": -0.6397084871944011, "heading_rate": -0.7702502514143325, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059658.3295994}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.388, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059658.3295994}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059658.429853, "x": -88.2361412672578, "y": 40.092836811141716, "z": 202.45549630760502, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7548618162215615, "steering_wheel_angle": -11.388, "front_wheel_angle": -0.6397084871944011, "heading_rate": -0.7615304372473778, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059658.429625}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.388, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059658.429625}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059658.5297248, "x": -88.2361412672578, "y": 40.092836811141716, "z": 202.45549630760502, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7662468162215617, "steering_wheel_angle": -11.388, "front_wheel_angle": -0.6397084871944011, "heading_rate": -0.7935030891928784, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059658.5295904}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.73, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.388, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059658.5295904}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059658.6297467, "x": -88.23613089356428, "y": 40.09284563405271, "z": 202.458488707629, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7693938162215614, "steering_wheel_angle": -11.388, "front_wheel_angle": -0.6397084871944011, "heading_rate": -0.8022229033598329, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059658.6295924}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.76, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.388, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059658.6295924}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059658.729724, "x": -88.23613089356428, "y": 40.09284563405271, "z": 202.458488707629, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7662468162215617, "steering_wheel_angle": -11.388, "front_wheel_angle": -0.6397084871944011, "heading_rate": -0.7935030891928784, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059658.7295873}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.73, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.388, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059658.7295873}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059658.8299067, "x": -88.23613089356428, "y": 40.09284563405271, "z": 202.458488707629, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7768068162215616, "steering_wheel_angle": -11.388, "front_wheel_angle": -0.6397084871944011, "heading_rate": -0.8225691364160608, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059658.8296154}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.388, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059658.8296154}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059658.9297066, "x": -88.23613089356428, "y": 40.09284563405271, "z": 202.458488707629, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7789428162215617, "steering_wheel_angle": -11.388, "front_wheel_angle": -0.6397084871944011, "heading_rate": -0.8283823458606973, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059658.9295864}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.388, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059658.9295864}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059659.029717, "x": -88.23613089356428, "y": 40.09284563405271, "z": 202.458488707629, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7875668162215614, "steering_wheel_angle": -11.388, "front_wheel_angle": -0.6397084871944011, "heading_rate": -0.8516351836392431, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059659.0295894}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.388, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059659.0295894}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059659.129732, "x": -88.23611702987986, "y": 40.09285253323473, "z": 202.48294134244497, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7908338162215616, "steering_wheel_angle": -11.388, "front_wheel_angle": -0.6397084871944011, "heading_rate": -0.8603549978061977, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059659.1295967}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.96, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.388, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059659.1295967}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059659.2298808, "x": -88.23611702987986, "y": 40.09285253323473, "z": 202.48294134244497, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8096868162215616, "steering_wheel_angle": -11.387, "front_wheel_angle": -0.6396361762549642, "heading_rate": -0.9096299232017084, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059659.2296047}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.387, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059659.2296047}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059659.3299603, "x": -88.23611702987986, "y": 40.09285253323473, "z": 202.48294134244497, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8187588162215613, "steering_wheel_angle": -11.381, "front_wheel_angle": -0.639202409207674, "heading_rate": -0.9320345670566468, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059659.3296542}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.21, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.381, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059659.3296542}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059659.4297462, "x": -88.23611702987986, "y": 40.09285253323473, "z": 202.48294134244497, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8314418162215613, "steering_wheel_angle": -11.375, "front_wheel_angle": -0.6387688110281188, "heading_rate": -0.9631007204644935, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059659.4296153}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.32, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.375, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059659.4296153}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059659.5299215, "x": -88.23611702987986, "y": 40.09285253323473, "z": 202.48294134244497, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8539188162215616, "steering_wheel_angle": -11.371, "front_wheel_angle": -0.6384798392931562, "heading_rate": -1.017603345719353, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059659.5295875}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.51, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.371, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059659.5295875}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059659.6300282, "x": -88.23609944465544, "y": 40.09285644639974, "z": 202.5440923177369, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8503218162215616, "steering_wheel_angle": -11.366, "front_wheel_angle": -0.6381187299548031, "heading_rate": -1.008144805859238, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059659.6296105}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.366, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059659.6296105}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059659.7298796, "x": -88.23609944465544, "y": 40.09285644639974, "z": 202.5440923177369, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8808468162215615, "steering_wheel_angle": -11.36, "front_wheel_angle": -0.6376855530832417, "heading_rate": -1.0795910261637376, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059659.7296042}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.73, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.36, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059659.7296042}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059659.8301098, "x": -88.23609944465544, "y": 40.09285644639974, "z": 202.5440923177369, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8672618162215615, "steering_wheel_angle": -11.334, "front_wheel_angle": -0.6358103942056382, "heading_rate": -1.0436515710281058, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059659.829667}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.334, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059659.829667}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059659.9297698, "x": -88.23609944465544, "y": 40.09285644639974, "z": 202.5440923177369, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9204338162215615, "steering_wheel_angle": -11.276, "front_wheel_angle": -0.6316386472019692, "heading_rate": -1.1545996473139093, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059659.9296176}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.04, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.276, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059659.9296176}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059660.029929, "x": -88.23609944465544, "y": 40.09285644639974, "z": 202.5440923177369, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9010388162215617, "steering_wheel_angle": -11.13, "front_wheel_angle": -0.6212054238537611, "heading_rate": -1.0875746522777512, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059660.0296025}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.13, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059660.0296025}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059660.129872, "x": -88.23607753583858, "y": 40.09285521107245, "z": 202.5729590930867, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.932286816221562, "steering_wheel_angle": -10.988, "front_wheel_angle": -0.6111494881301294, "heading_rate": -1.130315238707868, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059660.1296055}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.988, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059660.1296055}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059660.2297392, "x": -88.23607753583858, "y": 40.09285521107245, "z": 202.5729590930867, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9429588162215614, "steering_wheel_angle": -10.938, "front_wheel_angle": -0.6076296825741517, "heading_rate": -1.1436012803097886, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059660.2296135}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.21, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.938, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059660.2296135}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059660.3296988, "x": -88.23607753583858, "y": 40.09285521107245, "z": 202.5729590930867, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9443018162215617, "steering_wheel_angle": -10.752, "front_wheel_angle": -0.5946298994899736, "heading_rate": -1.1148086932969956, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059660.329584}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.752, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059660.329584}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059660.4297762, "x": -88.23607753583858, "y": 40.09285521107245, "z": 202.5729590930867, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9376068162215616, "steering_wheel_angle": -10.295, "front_wheel_angle": -0.5632926893370986, "heading_rate": -1.0287291825188967, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059660.4296293}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.17, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.295, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059660.4296293}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059660.5297167, "x": -88.23607753583858, "y": 40.09285521107245, "z": 202.5729590930867, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.932286816221562, "steering_wheel_angle": -9.729, "front_wheel_angle": -0.525589771594351, "heading_rate": -0.9357160136394527, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059660.5296104}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.729, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059660.5296104}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059660.6297767, "x": -88.23605530642945, "y": 40.09284681812994, "z": 202.58990887061688, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9416178162215614, "steering_wheel_angle": -9.165, "front_wheel_angle": -0.48913838618882877, "heading_rate": -0.8732750074617089, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059660.6295953}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.165, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059660.6295953}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059660.7297492, "x": -88.23605530642945, "y": 40.09284681812994, "z": 202.58990887061688, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9510468162215613, "steering_wheel_angle": -8.585, "front_wheel_angle": -0.45271825389859804, "heading_rate": -0.8113200473511119, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059660.7296104}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.27, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.585, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059660.7296104}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059660.8301792, "x": -88.23605530642945, "y": 40.09284681812994, "z": 202.58990887061688, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.919126816221562, "steering_wheel_angle": -7.914, "front_wheel_angle": -0.41181730785308945, "heading_rate": -0.6876085490559729, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059660.829709}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.914, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059660.829709}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059660.930027, "x": -88.23605530642945, "y": 40.09284681812994, "z": 202.58990887061688, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9633138162215618, "steering_wheel_angle": -7.112, "front_wheel_angle": -0.36451097246034825, "heading_rate": -0.6498473199124192, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059660.9296267}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.112, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059660.9296267}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059661.0297518, "x": -88.23605530642945, "y": 40.09284681812994, "z": 202.58990887061688, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9126218162215616, "steering_wheel_angle": -6.302, "front_wheel_angle": -0.31831517029575684, "heading_rate": -0.5123015437688626, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059661.0296168}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.302, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059661.0296168}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059661.129745, "x": -88.23603715350858, "y": 40.092832869143436, "z": 202.5757666914311, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9416178162215614, "steering_wheel_angle": -5.615, "front_wheel_angle": -0.28026955750127713, "heading_rate": -0.47224766351941094, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059661.1296155}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.615, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059661.1296155}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059661.2297013, "x": -88.23603715350858, "y": 40.092832869143436, "z": 202.5757666914311, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9230538162215614, "steering_wheel_angle": -4.878, "front_wheel_angle": -0.24051864752782273, "heading_rate": -0.3889773080192634, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059661.2295828}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.878, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059661.2295828}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059661.3297522, "x": -88.23603715350858, "y": 40.092832869143436, "z": 202.5757666914311, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9296388162215616, "steering_wheel_angle": -4.099, "front_wheel_angle": -0.1996078647932536, "heading_rate": -0.3247892490532565, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059661.3295844}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.11, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.099, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059661.3295844}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059661.4298263, "x": -88.23603715350858, "y": 40.092832869143436, "z": 202.5757666914311, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.932286816221562, "steering_wheel_angle": -3.328, "front_wheel_angle": -0.1601515208558921, "heading_rate": -0.2606012762116036, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059661.429602}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.328, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059661.429602}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059661.5298777, "x": -88.23603715350858, "y": 40.092832869143436, "z": 202.5757666914311, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9256818162215614, "steering_wheel_angle": -2.634, "front_wheel_angle": -0.12545350979025102, "heading_rate": -0.20099710918318997, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059661.5296366}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.634, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059661.5296366}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059661.62976, "x": -88.23602250348327, "y": 40.09281748428084, "z": 202.56901607661084, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9283178162215613, "steering_wheel_angle": -1.888, "front_wheel_angle": -0.08896232368511868, "heading_rate": -0.14285578813799304, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059661.6295936}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.888, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059661.6295936}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059661.72977, "x": -88.23602250348327, "y": 40.09281748428084, "z": 202.56901607661084, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9389418162215613, "steering_wheel_angle": -1.155, "front_wheel_angle": -0.05387021460892978, "heading_rate": -0.08804514527757323, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059661.729599}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059661.729599}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059661.8297467, "x": -88.23602250348327, "y": 40.09281748428084, "z": 202.56901607661084, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9309618162215614, "steering_wheel_angle": -0.463, "front_wheel_angle": -0.021393459854055687, "heading_rate": -0.03443535307181546, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059661.829594}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059661.829594}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059661.9298332, "x": -88.23602250348327, "y": 40.09281748428084, "z": 202.56901607661084, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9296388162215616, "steering_wheel_angle": 0.209, "front_wheel_angle": 0.009624584547123486, "heading_rate": 0.015452446858671892, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059661.9296339}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.11, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.209, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059661.9296339}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059662.0297246, "x": -88.23602250348327, "y": 40.09281748428084, "z": 202.56901607661084, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9296388162215616, "steering_wheel_angle": 0.884, "front_wheel_angle": 0.04107831847674268, "heading_rate": 0.06598707694558499, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059662.0296078}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.11, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.884, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059662.0296078}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059662.1296864, "x": -88.23602250348327, "y": 40.09281748428084, "z": 202.56901607661084, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9336138162215617, "steering_wheel_angle": 1.562, "front_wheel_angle": 0.07326466669834879, "heading_rate": 0.11869515298725022, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059662.1295788}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.14, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.562, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059662.1295788}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059662.2298079, "x": -88.23600826933202, "y": 40.092802794930265, "z": 202.57399259164401, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.932286816221562, "steering_wheel_angle": 2.215, "front_wheel_angle": 0.10485832855666462, "heading_rate": 0.16978872289301233, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059662.2296107}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.215, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059662.2296107}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059662.3297775, "x": -88.23600826933202, "y": 40.092802794930265, "z": 202.57399259164401, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9256818162215614, "steering_wheel_angle": 2.652, "front_wheel_angle": 0.12634410864590748, "heading_rate": 0.2024392391859947, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059662.329619}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.652, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059662.329619}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059662.4297554, "x": -88.23600826933202, "y": 40.092802794930265, "z": 202.57399259164401, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9309618162215614, "steering_wheel_angle": 3.203, "front_wheel_angle": 0.15384628789307986, "heading_rate": 0.2495684689182119, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059662.4295866}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.203, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059662.4295866}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059662.530029, "x": -88.23600826933202, "y": 40.092802794930265, "z": 202.57399259164401, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9296388162215616, "steering_wheel_angle": 3.837, "front_wheel_angle": 0.1860884195509535, "heading_rate": 0.3022561562340317, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059662.5296886}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.11, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.837, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059662.5296886}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059662.629693, "x": -88.23599266604496, "y": 40.092789753982174, "z": 202.58237468388367, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.932286816221562, "steering_wheel_angle": 4.349, "front_wheel_angle": 0.2126187249413427, "heading_rate": 0.3482778543172252, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059662.6295831}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.349, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059662.6295831}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059662.729699, "x": -88.23599266604496, "y": 40.092789753982174, "z": 202.58237468388367, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9362738162215614, "steering_wheel_angle": 4.851, "front_wheel_angle": 0.23908219194417027, "heading_rate": 0.396084241682975, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059662.7295797}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.851, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059662.7295797}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059662.829729, "x": -88.23599266604496, "y": 40.092789753982174, "z": 202.58237468388367, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9429588162215614, "steering_wheel_angle": 5.323, "front_wheel_angle": 0.2643932398935426, "heading_rate": 0.4452259426431417, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059662.8296094}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.21, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.323, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059662.8296094}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059662.929902, "x": -88.23599266604496, "y": 40.092789753982174, "z": 202.58237468388367, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9564788162215616, "steering_wheel_angle": 5.693, "front_wheel_angle": 0.28453954127254016, "heading_rate": 0.49241024079479473, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059662.929677}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.693, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059662.929677}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059663.030022, "x": -88.23599266604496, "y": 40.092789753982174, "z": 202.58237468388367, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9564788162215616, "steering_wheel_angle": 5.979, "front_wheel_angle": 0.30030352674397076, "heading_rate": 0.5213565433546464, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059663.0296667}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.979, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059663.0296667}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059663.1299748, "x": -88.23597433448575, "y": 40.09277951889076, "z": 202.5796525005328, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9605738162215616, "steering_wheel_angle": 6.106, "front_wheel_angle": 0.3073587321795233, "heading_rate": 0.538122148229566, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059663.12963}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.106, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059663.12963}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059663.2298172, "x": -88.23597433448575, "y": 40.09277951889076, "z": 202.5796525005328, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.968817816221562, "steering_wheel_angle": 6.138, "front_wheel_angle": 0.30914185937900573, "heading_rate": 0.5489370746203415, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059663.229611}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.138, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059663.229611}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059663.3299735, "x": -88.23597433448575, "y": 40.09277951889076, "z": 202.5796525005328, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9564788162215616, "steering_wheel_angle": 6.16, "front_wheel_angle": 0.3103690378340812, "heading_rate": 0.5399865287349658, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059663.3298013}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.16, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059663.3298013}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059663.429708, "x": -88.23597433448575, "y": 40.09277951889076, "z": 202.5796525005328, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.001086816221561, "steering_wheel_angle": 6.185, "front_wheel_angle": 0.3117648271869615, "heading_rate": 0.5828636887813615, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059663.429585}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.63, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.185, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059663.429585}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059663.52982, "x": -88.23597433448575, "y": 40.09277951889076, "z": 202.5796525005328, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9715818162215615, "steering_wheel_angle": 6.244, "front_wheel_angle": 0.31506426195656856, "heading_rate": 0.5627221658260543, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059663.5296876}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.42, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.244, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059663.5296876}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059663.6297143, "x": -88.23595257560771, "y": 40.09277296195404, "z": 202.58197250353712, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9925668162215615, "steering_wheel_angle": 6.307, "front_wheel_angle": 0.31859576597512146, "heading_rate": 0.5888010913719395, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059663.6295853}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059663.6295853}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059663.7297392, "x": -88.23595257560771, "y": 40.09277296195404, "z": 202.58197250353712, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": 6.312, "front_wheel_angle": 0.3188764165557441, "heading_rate": 0.5906462724512568, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059663.7296133}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.312, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059663.7296133}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059663.8298206, "x": -88.23595257560771, "y": 40.09277296195404, "z": 202.58197250353712, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": 6.296, "front_wheel_angle": 0.3179785279048344, "heading_rate": 0.5991511921655628, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059663.829634}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.296, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059663.829634}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059663.9298873, "x": -88.23595257560771, "y": 40.09277296195404, "z": 202.58197250353712, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9996618162215616, "steering_wheel_angle": 6.28, "front_wheel_angle": 0.3170812007179195, "heading_rate": 0.5922139557036002, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059663.9296243}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.28, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059663.9296243}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059664.0297368, "x": -88.23595257560771, "y": 40.09277296195404, "z": 202.58197250353712, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": 6.279, "front_wheel_angle": 0.3170251363870654, "heading_rate": 0.5869754605637868, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059664.0295901}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.279, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059664.0295901}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059664.1297314, "x": -88.23592845085089, "y": 40.09277098750076, "z": 202.5687347373179, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.012558816221562, "steering_wheel_angle": 6.29, "front_wheel_angle": 0.317641964469753, "heading_rate": 0.6048936193620325, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059664.1295865}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.71, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.29, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059664.1295865}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059664.2297447, "x": -88.23592845085089, "y": 40.09277098750076, "z": 202.5687347373179, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0096788162215615, "steering_wheel_angle": 6.295, "front_wheel_angle": 0.3179224285174432, "heading_rate": 0.6028944804225173, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059664.2296097}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.295, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059664.2296097}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059664.32971, "x": -88.23592845085089, "y": 40.09277098750076, "z": 202.5687347373179, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": 6.294, "front_wheel_angle": 0.3178663313230127, "heading_rate": 0.6092068130265584, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059664.3295827}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.294, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059664.3295827}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059664.42974, "x": -88.23592845085089, "y": 40.09277098750076, "z": 202.5687347373179, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0068068162215615, "steering_wheel_angle": 6.292, "front_wheel_angle": 0.3177541435120047, "heading_rate": 0.5999832860192391, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059664.4296105}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.292, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059664.4296105}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059664.5297363, "x": -88.23592845085089, "y": 40.09277098750076, "z": 202.5687347373179, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.022701816221562, "steering_wheel_angle": 6.278, "front_wheel_angle": 0.3169690742450637, "heading_rate": 0.6124916323565478, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059664.52961}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.78, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.278, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059664.52961}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059664.629991, "x": -88.23590400140701, "y": 40.09277405171843, "z": 202.5993502766148, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.015446816221562, "steering_wheel_angle": 6.244, "front_wheel_angle": 0.31506426195656856, "heading_rate": 0.6021891050581983, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059664.6296213}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.73, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.244, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059664.6296213}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059664.7297916, "x": -88.23590400140701, "y": 40.09277405171843, "z": 202.5993502766148, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": 6.216, "front_wheel_angle": 0.31349748562010227, "heading_rate": 0.610385609866236, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059664.729625}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.216, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059664.729625}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059664.8299615, "x": -88.23590400140701, "y": 40.09277405171843, "z": 202.5993502766148, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.037361816221561, "steering_wheel_angle": 6.205, "front_wheel_angle": 0.3128824327188308, "heading_rate": 0.6166883629488276, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059664.8296635}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.88, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.205, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059664.8296635}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059664.9297552, "x": -88.23590400140701, "y": 40.09277405171843, "z": 202.5993502766148, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.037361816221561, "steering_wheel_angle": 6.175, "front_wheel_angle": 0.31120634929287616, "heading_rate": 0.613160852947412, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059664.9295902}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.88, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.175, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059664.9295902}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059665.0297897, "x": -88.23590400140701, "y": 40.09277405171843, "z": 202.5993502766148, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.037361816221561, "steering_wheel_angle": 6.047, "front_wheel_angle": 0.3040768443308045, "heading_rate": 0.5981981546653288, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059665.029595}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.88, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.047, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059665.029595}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059665.1297705, "x": -88.23588085168656, "y": 40.092781842891306, "z": 202.59873531580288, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.022701816221562, "steering_wheel_angle": 5.705, "front_wheel_angle": 0.2851975643969096, "heading_rate": 0.5474409601022275, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059665.129618}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.78, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.705, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059665.129618}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059665.2297275, "x": -88.23588085168656, "y": 40.092781842891306, "z": 202.59873531580288, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0462538162215616, "steering_wheel_angle": 5.121, "front_wheel_angle": 0.25350867058431414, "heading_rate": 0.49994869037160994, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059665.2295911}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.94, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.121, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059665.2295911}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059665.3297148, "x": -88.23588085168656, "y": 40.092781842891306, "z": 202.59873531580288, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.022701816221562, "steering_wheel_angle": 4.403, "front_wheel_angle": 0.21544352988078802, "heading_rate": 0.40861519856473316, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059665.3295856}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.78, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.403, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059665.3295856}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059665.4297419, "x": -88.23588085168656, "y": 40.092781842891306, "z": 202.59873531580288, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.018342816221562, "steering_wheel_angle": 3.743, "front_wheel_angle": 0.18126627721477906, "heading_rate": 0.34006667316319006, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059665.4295905}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.75, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.743, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059665.4295905}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059665.5297613, "x": -88.23588085168656, "y": 40.092781842891306, "z": 202.59873531580288, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.025617816221562, "steering_wheel_angle": 3.085, "front_wheel_angle": 0.14791687518566335, "heading_rate": 0.279384709383131, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059665.5295923}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.8, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.085, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059665.5295923}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059665.629775, "x": -88.23585981055054, "y": 40.0927938337206, "z": 202.58783429768846, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.022701816221562, "steering_wheel_angle": 2.347, "front_wheel_angle": 0.11131867069497897, "heading_rate": 0.2087156676687163, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059665.6295981}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.78, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.347, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059665.6295981}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059665.7297585, "x": -88.23585981055054, "y": 40.0927938337206, "z": 202.58783429768846, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.025617816221562, "steering_wheel_angle": 1.577, "front_wheel_angle": 0.07398373040426494, "heading_rate": 0.1389731478691661, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059665.7295916}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.8, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.577, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059665.7295916}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059665.8300166, "x": -88.23585981055054, "y": 40.0927938337206, "z": 202.58783429768846, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.018342816221562, "steering_wheel_angle": 0.815, "front_wheel_angle": 0.03783657922090566, "heading_rate": 0.07023811133490793, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059665.8296504}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.75, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.815, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059665.8296504}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059665.9297838, "x": -88.23585981055054, "y": 40.0927938337206, "z": 202.58783429768846, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": 0.111, "front_wheel_angle": 0.005105022404758634, "heading_rate": 0.009452350159818932, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059665.9296079}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.111, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059665.9296079}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059666.0297835, "x": -88.23585981055054, "y": 40.0927938337206, "z": 202.58783429768846, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.032942816221562, "steering_wheel_angle": -0.569, "front_wheel_angle": -0.02632860349382649, "heading_rate": -0.04989189089649433, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059666.0296319}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.569, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059666.0296319}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059666.1297839, "x": -88.23583887896051, "y": 40.09280758564565, "z": 202.60248253750925, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": -1.253, "front_wheel_angle": -0.05851984132000664, "heading_rate": -0.11030783652908943, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059666.1296377}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.253, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059666.1296377}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059666.229864, "x": -88.23583887896051, "y": 40.09280758564565, "z": 202.60248253750925, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.032942816221562, "steering_wheel_angle": -1.868, "front_wheel_angle": -0.08799501589744743, "heading_rate": -0.16714092789507384, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059666.229627}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.868, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059666.229627}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059666.3298464, "x": -88.23583887896051, "y": 40.09280758564565, "z": 202.60248253750925, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.035886816221562, "steering_wheel_angle": -2.53, "front_wheel_angle": -0.12031733981149102, "heading_rate": -0.22999583865496537, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059666.329649}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.53, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059666.329649}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059666.4297588, "x": -88.23583887896051, "y": 40.09280758564565, "z": 202.60248253750925, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": -3.162, "front_wheel_angle": -0.15178357901988207, "heading_rate": -0.2933725597726224, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059666.4295895}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.162, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059666.4295895}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059666.5298533, "x": -88.23583887896051, "y": 40.09280758564565, "z": 202.60248253750925, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": -3.772, "front_wheel_angle": -0.18275237983588233, "heading_rate": -0.3544683976790397, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059666.5295959}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.772, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059666.5295959}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059666.629786, "x": -88.23581502894744, "y": 40.09282018632586, "z": 202.5919726548157, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": -4.317, "front_wheel_angle": -0.21094720828459623, "heading_rate": -0.4173918330952098, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059666.6296167}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059666.6296167}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059666.7297182, "x": -88.23581502894744, "y": 40.09282018632586, "z": 202.5919726548157, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": -4.806, "front_wheel_angle": -0.23669112336420825, "heading_rate": -0.47771380749953557, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059666.7295864}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.806, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059666.7295864}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059666.829721, "x": -88.23581502894744, "y": 40.09282018632586, "z": 202.5919726548157, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": -5.211, "front_wheel_angle": -0.25834844036265187, "heading_rate": -0.523346552243663, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059666.8295832}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.211, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059666.8295832}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059666.929811, "x": -88.23581502894744, "y": 40.09282018632586, "z": 202.5919726548157, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": -5.627, "front_wheel_angle": -0.28092567189491335, "heading_rate": -0.5895125377690271, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059666.9296198}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.627, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059666.9296198}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059667.029849, "x": -88.23581502894744, "y": 40.09282018632586, "z": 202.5919726548157, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": -5.953, "front_wheel_angle": -0.29886337529158524, "heading_rate": -0.6197930443244543, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059667.0296054}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.953, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059667.0296054}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059667.1297965, "x": -88.23578673907544, "y": 40.092829030696294, "z": 202.60204658198336, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": -6.168, "front_wheel_angle": -0.3108155434481843, "heading_rate": -0.6562566539692225, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059667.1295984}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.168, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059667.1295984}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059667.2299855, "x": -88.23578673907544, "y": 40.092829030696294, "z": 202.60204658198336, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": -6.281, "front_wheel_angle": -0.3171372672378817, "heading_rate": -0.6705335863290267, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059667.2296615}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.281, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059667.2296615}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059667.3297553, "x": -88.23578673907544, "y": 40.092829030696294, "z": 202.60204658198336, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": -6.328, "front_wheel_angle": -0.3197748677259052, "heading_rate": -0.6868559003938716, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059667.3295534}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.328, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059667.3295534}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059667.4297566, "x": -88.23578673907544, "y": 40.092829030696294, "z": 202.60204658198336, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": -6.339, "front_wheel_angle": -0.3203928797604564, "heading_rate": -0.6882786477373206, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059667.42959}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.339, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059667.42959}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059667.529799, "x": -88.23578673907544, "y": 40.092829030696294, "z": 202.60204658198336, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": -6.349, "front_wheel_angle": -0.3209549403278845, "heading_rate": -0.7012607735345975, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059667.5295959}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.349, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059667.5295959}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059667.6297498, "x": -88.23575485676719, "y": 40.0928310804009, "z": 202.60797428788248, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": -6.385, "front_wheel_angle": -0.322980187570576, "heading_rate": -0.7060081359377038, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059667.629586}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.385, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059667.629586}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059667.7297587, "x": -88.23575485676719, "y": 40.0928310804009, "z": 202.60797428788248, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": -6.411, "front_wheel_angle": -0.32444465178230475, "heading_rate": -0.6976208985603121, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059667.729613}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.411, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059667.729613}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059667.829831, "x": -88.23575485676719, "y": 40.0928310804009, "z": 202.60797428788248, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": -6.445, "front_wheel_angle": -0.32636198868426886, "heading_rate": -0.7139497650733921, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059667.8296103}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.445, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059667.8296103}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059667.9298067, "x": -88.23575485676719, "y": 40.0928310804009, "z": 202.60797428788248, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": -6.454, "front_wheel_angle": -0.326869950527716, "heading_rate": -0.7257389289210597, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059667.9296007}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.454, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059667.9296007}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059668.0300295, "x": -88.23575485676719, "y": 40.0928310804009, "z": 202.60797428788248, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": -6.383, "front_wheel_angle": -0.3228675985928032, "heading_rate": -0.7057440486217788, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059668.0296428}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.383, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059668.0296428}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059668.1297677, "x": -88.2357228530664, "y": 40.09282560834119, "z": 202.5542164811391, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.142353816221561, "steering_wheel_angle": -6.208, "front_wheel_angle": -0.3130501483648211, "heading_rate": -0.703022749602508, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059668.1295874}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.208, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059668.1295874}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059668.2298076, "x": -88.2357228530664, "y": 40.09282560834119, "z": 202.5542164811391, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": -5.965, "front_wheel_angle": -0.2995278832608322, "heading_rate": -0.6610657404376461, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059668.2295988}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.965, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059668.2295988}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059668.3297834, "x": -88.2357228530664, "y": 40.09282560834119, "z": 202.5542164811391, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": -5.602, "front_wheel_angle": -0.2795590966119846, "heading_rate": -0.6055531009642169, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059668.3295887}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.602, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059668.3295887}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059668.429753, "x": -88.2357228530664, "y": 40.09282560834119, "z": 202.5542164811391, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.142353816221561, "steering_wheel_angle": -5.002, "front_wheel_angle": -0.24713329997929342, "heading_rate": -0.5479435144345663, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059668.42962}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.002, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059668.42962}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059668.5298288, "x": -88.2357228530664, "y": 40.09282560834119, "z": 202.5542164811391, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": -4.295, "front_wheel_angle": -0.20979909083073664, "heading_rate": -0.45580845505671164, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059668.5296233}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.295, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059668.5296233}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059668.6298728, "x": -88.23569406977168, "y": 40.09281357592833, "z": 202.48927722434397, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": -3.587, "front_wheel_angle": -0.1732960580767805, "heading_rate": -0.3692501760781773, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059668.6296334}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.587, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059668.6296334}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059668.7297702, "x": -88.23569406977168, "y": 40.09281357592833, "z": 202.48927722434397, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": -2.898, "front_wheel_angle": -0.13856486511253374, "heading_rate": -0.29852846873933997, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059668.7295902}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.898, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059668.7295902}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059668.8301713, "x": -88.23569406977168, "y": 40.09281357592833, "z": 202.48927722434397, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": -2.153, "front_wheel_angle": -0.1018326499275583, "heading_rate": -0.2187421500622389, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059668.8296607}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.153, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059668.8296607}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059668.9297543, "x": -88.23569406977168, "y": 40.09281357592833, "z": 202.48927722434397, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": -1.402, "front_wheel_angle": -0.06561372025590478, "heading_rate": -0.1386029008434485, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059668.9296153}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.402, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059668.9296153}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059669.0297666, "x": -88.23569406977168, "y": 40.09281357592833, "z": 202.48927722434397, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": -0.659, "front_wheel_angle": -0.030529919437705017, "heading_rate": -0.06537342105706054, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059669.0296102}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.659, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059669.0296102}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059669.1302466, "x": -88.23566879960774, "y": 40.092798135448035, "z": 202.45544919600485, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": 0.026, "front_wheel_angle": 0.001194436781101673, "heading_rate": 0.0025195162833169674, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059669.1297193}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059669.1297193}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059669.229742, "x": -88.23566879960774, "y": 40.092798135448035, "z": 202.45544919600485, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": 0.709, "front_wheel_angle": 0.03286841786692406, "heading_rate": 0.07038430498200092, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059669.2295864}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.709, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059669.2295864}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059669.3299026, "x": -88.23566879960774, "y": 40.092798135448035, "z": 202.45544919600485, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": 1.395, "front_wheel_angle": 0.06527978326702322, "heading_rate": 0.13993837268258708, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059669.3295877}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.395, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059669.3295877}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059669.4298892, "x": -88.23566879960774, "y": 40.092798135448035, "z": 202.45544919600485, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": 2.067, "front_wheel_angle": 0.09764489686616702, "heading_rate": 0.20968795642500487, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059669.4296556}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.067, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059669.4296556}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059669.5298483, "x": -88.23566879960774, "y": 40.092798135448035, "z": 202.45544919600485, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": 2.667, "front_wheel_angle": 0.12708664701066283, "heading_rate": 0.2735189781811143, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059669.529618}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.667, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059669.529618}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059669.6299498, "x": -88.23564381565951, "y": 40.0927838122957, "z": 202.45679556158933, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": 3.253, "front_wheel_angle": 0.15636539305059569, "heading_rate": 0.33747459647158135, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059669.6296175}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.253, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059669.6296175}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059669.7297616, "x": -88.23564381565951, "y": 40.0927838122957, "z": 202.45679556158933, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": 3.791, "front_wheel_angle": 0.18372679636438888, "heading_rate": 0.39777599186312107, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059669.7295954}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.791, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059669.7295954}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059669.8297184, "x": -88.23564381565951, "y": 40.0927838122957, "z": 202.45679556158933, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": 4.098, "front_wheel_angle": 0.19955604017239972, "heading_rate": 0.4329368559887729, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059669.8295817}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.098, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059669.8295817}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059669.929756, "x": -88.23564381565951, "y": 40.0927838122957, "z": 202.45679556158933, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": 4.238, "front_wheel_angle": 0.20682838883357657, "heading_rate": 0.44916515320080047, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059669.929582}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.238, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059669.929582}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059670.0301561, "x": -88.23564381565951, "y": 40.0927838122957, "z": 202.45679556158933, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": 4.317, "front_wheel_angle": 0.21094720828459623, "heading_rate": 0.45168655284852366, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059670.0297248}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059670.0297248}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059670.130024, "x": -88.23561670581043, "y": 40.092773654351305, "z": 202.45400874529545, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": 4.552, "front_wheel_angle": 0.22326495285782397, "heading_rate": 0.47893392586394223, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059670.1296883}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.552, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059670.1296883}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059670.2297392, "x": -88.23561670581043, "y": 40.092773654351305, "z": 202.45400874529545, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": 4.757, "front_wheel_angle": 0.23409179617890097, "heading_rate": 0.4946257673280689, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059670.2295926}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.757, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059670.2295926}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059670.3297932, "x": -88.23561670581043, "y": 40.092773654351305, "z": 202.45400874529545, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": 4.769, "front_wheel_angle": 0.23472795463037735, "heading_rate": 0.5044276738480231, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059670.3296256}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.769, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059670.3296256}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059670.42983, "x": -88.23561670581043, "y": 40.092773654351305, "z": 202.45400874529545, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": 4.879, "front_wheel_angle": 0.2405718757874079, "heading_rate": 0.5174780152008445, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059670.429593}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.879, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059670.429593}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059670.5300171, "x": -88.23561670581043, "y": 40.092773654351305, "z": 202.45400874529545, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": 5.085, "front_wheel_angle": 0.2515771309522035, "heading_rate": 0.5331210100479727, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059670.5296261}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.085, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059670.5296261}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059670.6298306, "x": -88.23558793306475, "y": 40.09276889938905, "z": 202.47357025060026, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": 5.277, "front_wheel_angle": 0.2619075888437103, "heading_rate": 0.5654499581052005, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059670.6296196}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059670.6296196}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059670.729796, "x": -88.23558793306475, "y": 40.09276889938905, "z": 202.47357025060026, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": 5.471, "front_wheel_angle": 0.27241886382979963, "heading_rate": 0.5794620931435266, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059670.7296143}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.471, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059670.7296143}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059670.8297067, "x": -88.23558793306475, "y": 40.09276889938905, "z": 202.47357025060026, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": 5.596, "front_wheel_angle": 0.279231307103155, "heading_rate": 0.5947246780197329, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059670.8295834}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.596, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059670.8295834}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059670.9297612, "x": -88.23558793306475, "y": 40.09276889938905, "z": 202.47357025060026, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": 5.607, "front_wheel_angle": 0.279832310251356, "heading_rate": 0.5960740062367792, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059670.929637}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.607, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059670.929637}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059671.0298848, "x": -88.23558793306475, "y": 40.09276889938905, "z": 202.47357025060026, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": 5.607, "front_wheel_angle": 0.279832310251356, "heading_rate": 0.6061769554950298, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059671.0296292}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.607, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059671.0296292}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059671.1306355, "x": -88.23555928946395, "y": 40.092770067842295, "z": 202.486366672074, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": 5.606, "front_wheel_angle": 0.2797776634699536, "heading_rate": 0.586972747410782, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059671.1296635}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059671.1296635}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059671.2298322, "x": -88.23555928946395, "y": 40.092770067842295, "z": 202.486366672074, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": 5.606, "front_wheel_angle": 0.2797776634699536, "heading_rate": 0.5959512980403923, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059671.2296233}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059671.2296233}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059671.3298175, "x": -88.23555928946395, "y": 40.092770067842295, "z": 202.486366672074, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": 5.606, "front_wheel_angle": 0.2797776634699536, "heading_rate": 0.5959512980403923, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059671.3296375}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059671.3296375}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059671.4297588, "x": -88.23555928946395, "y": 40.092770067842295, "z": 202.486366672074, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": 5.607, "front_wheel_angle": 0.279832310251356, "heading_rate": 0.5870936068961121, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059671.4296105}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.607, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059671.4296105}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059671.5297484, "x": -88.23555928946395, "y": 40.092770067842295, "z": 202.486366672074, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": 5.61, "front_wheel_angle": 0.27999626275975625, "heading_rate": 0.5874562350376683, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059671.529605}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.61, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059671.529605}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059671.6297293, "x": -88.23553239138396, "y": 40.09277698163777, "z": 202.53521703761257, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": 5.608, "front_wheel_angle": 0.2798869590599733, "heading_rate": 0.5872144746611544, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059671.6296084}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.608, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059671.6296084}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059671.7297485, "x": -88.23553239138396, "y": 40.09277698163777, "z": 202.53521703761257, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": 5.596, "front_wheel_angle": 0.279231307103155, "heading_rate": 0.5857646075410929, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059671.72961}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.596, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059671.72961}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059671.8300164, "x": -88.23553239138396, "y": 40.09277698163777, "z": 202.53521703761257, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": 5.566, "front_wheel_angle": 0.2775934519452419, "heading_rate": 0.5732404307782365, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059671.8296366}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.566, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059671.8296366}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059671.9303596, "x": -88.23553239138396, "y": 40.09277698163777, "z": 202.53521703761257, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": 5.41, "front_wheel_angle": 0.26910574686516625, "heading_rate": 0.5548232306231048, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059671.929676}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.41, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059671.929676}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059672.0298374, "x": -88.23553239138396, "y": 40.09277698163777, "z": 202.53521703761257, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": 5.033, "front_wheel_angle": 0.24879150807234132, "heading_rate": 0.5110872728300025, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059672.029632}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.033, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059672.029632}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059672.1297054, "x": -88.23553239138396, "y": 40.09277698163777, "z": 202.53521703761257, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": 4.46, "front_wheel_angle": 0.21843090969259027, "heading_rate": 0.4396094894467531, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059672.1295762}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.46, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059672.1295762}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059672.2297738, "x": -88.2355088447274, "y": 40.09278852471763, "z": 202.59744405339558, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": 3.86, "front_wheel_angle": 0.18727056694569966, "heading_rate": 0.36935927198913165, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059672.2296093}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.86, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059672.2296093}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059672.3297193, "x": -88.2355088447274, "y": 40.09278852471763, "z": 202.59744405339558, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": 3.271, "front_wheel_angle": 0.15727324444229987, "heading_rate": 0.3091127914437504, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059672.3295827}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.271, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059672.3295827}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059672.4297004, "x": -88.2355088447274, "y": 40.09278852471763, "z": 202.59744405339558, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": 2.643, "front_wheel_angle": 0.12589874828322062, "heading_rate": 0.2506643227480243, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059672.429576}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.643, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059672.429576}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059672.529954, "x": -88.2355088447274, "y": 40.09278852471763, "z": 202.59744405339558, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": 1.911, "front_wheel_angle": 0.0900754232560391, "heading_rate": 0.17887559671304565, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059672.5296125}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.911, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059672.5296125}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059672.6299193, "x": -88.23548807583546, "y": 40.09280329098754, "z": 202.56970886000303, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": 1.196, "front_wheel_angle": 0.05581391675151875, "heading_rate": 0.10890664495313022, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059672.6296215}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.196, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059672.6296215}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059672.729784, "x": -88.23548807583546, "y": 40.09280329098754, "z": 202.56970886000303, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": 0.525, "front_wheel_angle": 0.024278342961108788, "heading_rate": 0.04809194898065222, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059672.7295923}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.525, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059672.7295923}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059672.83001, "x": -88.23548807583546, "y": 40.09280329098754, "z": 202.56970886000303, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": -0.127, "front_wheel_angle": -0.005842111522187375, "heading_rate": -0.011752818998029902, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059672.8296044}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.127, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059672.8296044}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059672.929757, "x": -88.23548807583546, "y": 40.09280329098754, "z": 202.56970886000303, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": -0.65, "front_wheel_angle": -0.030109326811075615, "heading_rate": -0.05964860716601501, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059672.9296079}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.65, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059672.9296079}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059673.029983, "x": -88.23548807583546, "y": 40.09280329098754, "z": 202.56970886000303, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": -0.951, "front_wheel_angle": -0.044231979508704666, "heading_rate": -0.08904037831989355, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059673.0295985}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.951, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059673.0295985}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059673.1298642, "x": -88.23546680422939, "y": 40.09281889831452, "z": 202.57935936469883, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": -1.037, "front_wheel_angle": -0.04828851287781835, "heading_rate": -0.09721848256830325, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059673.1296132}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.037, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059673.1296132}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059673.2302732, "x": -88.23546680422939, "y": 40.09281889831452, "z": 202.57935936469883, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": -1.152, "front_wheel_angle": -0.05372807979377048, "heading_rate": -0.10987052969374897, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059673.2296312}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059673.2296312}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059673.329911, "x": -88.23546680422939, "y": 40.09281889831452, "z": 202.57935936469883, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": -1.237, "front_wheel_angle": -0.05775984750252602, "heading_rate": -0.11813296441184541, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059673.3296058}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.237, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059673.3296058}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059673.4298074, "x": -88.23546680422939, "y": 40.09281889831452, "z": 202.57935936469883, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": -1.394, "front_wheel_angle": -0.065232083376589, "heading_rate": -0.13345645729515646, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059673.4295917}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.394, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059673.4295917}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059673.5297785, "x": -88.23546680422939, "y": 40.09281889831452, "z": 202.57935936469883, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": -1.655, "front_wheel_angle": -0.07772783697973093, "heading_rate": -0.16155000904918687, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059673.5295887}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.655, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059673.5295887}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059673.6297545, "x": -88.2354429238205, "y": 40.09283383800591, "z": 202.59360142825338, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": -1.928, "front_wheel_angle": -0.09089862814075002, "heading_rate": -0.18621621369220095, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059673.6295862}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.928, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059673.6295862}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059673.7298803, "x": -88.2354429238205, "y": 40.09283383800591, "z": 202.59360142825338, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": -2.139, "front_wheel_angle": -0.10115019919703841, "heading_rate": -0.21052611965548979, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059673.729605}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.139, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059673.729605}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059673.8297231, "x": -88.2354429238205, "y": 40.09283383800591, "z": 202.59360142825338, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": -2.274, "front_wheel_angle": -0.10774277041308192, "heading_rate": -0.2175907715597936, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059673.8295827}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.274, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059673.8295827}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059673.929762, "x": -88.2354429238205, "y": 40.09283383800591, "z": 202.59360142825338, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": -2.376, "front_wheel_angle": -0.1127413974690949, "heading_rate": -0.2313080062459168, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059673.9295847}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.376, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059673.9295847}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059674.0297894, "x": -88.2354429238205, "y": 40.09283383800591, "z": 202.59360142825338, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": -2.488, "front_wheel_angle": -0.11824769175814974, "heading_rate": -0.23899606052947553, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059674.0295842}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.488, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059674.0295842}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059674.1298249, "x": -88.23541687752109, "y": 40.09284682901184, "z": 202.60548033249788, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": -2.631, "front_wheel_angle": -0.12530512402413418, "heading_rate": -0.24946992465468093, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059674.1295984}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.631, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059674.1295984}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059674.2297091, "x": -88.23541687752109, "y": 40.09284682901184, "z": 202.60548033249788, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": -2.815, "front_wheel_angle": -0.1344312874926249, "heading_rate": -0.26785243382101287, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059674.229577}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.815, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059674.229577}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059674.32993, "x": -88.23541687752109, "y": 40.09284682901184, "z": 202.60548033249788, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": -3.066, "front_wheel_angle": -0.1469641854700623, "heading_rate": -0.3024236762478391, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059674.3296204}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.066, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059674.3296204}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059674.429854, "x": -88.23541687752109, "y": 40.09284682901184, "z": 202.60548033249788, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": -3.375, "front_wheel_angle": -0.16252875478333606, "heading_rate": -0.3247476356251498, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059674.4295962}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.375, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059674.4295962}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059674.5297632, "x": -88.23541687752109, "y": 40.09284682901184, "z": 202.60548033249788, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": -3.734, "front_wheel_angle": -0.1808053585790176, "heading_rate": -0.3563204573472548, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059674.529589}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.734, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059674.529589}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059674.6297348, "x": -88.23538918139371, "y": 40.09285647679831, "z": 202.60394252371955, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": -4.119, "front_wheel_angle": -0.20064472054495194, "heading_rate": -0.3900790474005071, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059674.6295779}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.119, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059674.6295779}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059674.7298057, "x": -88.23538918139371, "y": 40.09285647679831, "z": 202.60394252371955, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": -4.465, "front_wheel_angle": -0.2186932380495139, "heading_rate": -0.4262641704967527, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059674.7296174}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.465, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059674.7296174}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059674.8297305, "x": -88.23538918139371, "y": 40.09285647679831, "z": 202.60394252371955, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": -4.804, "front_wheel_angle": -0.2365849411570564, "heading_rate": -0.46995690793639017, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059674.8295786}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.804, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059674.8295786}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059674.9297936, "x": -88.23538918139371, "y": 40.09285647679831, "z": 202.60394252371955, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": -5.136, "front_wheel_angle": -0.25431421349747413, "heading_rate": -0.48942301807326183, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059674.9295933}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.136, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059674.9295933}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059675.0300615, "x": -88.23538918139371, "y": 40.09285647679831, "z": 202.60394252371955, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": -5.532, "front_wheel_angle": -0.2757394113631081, "heading_rate": -0.532736254712553, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059675.0296957}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.532, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059675.0296957}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059675.1297145, "x": -88.23536054884153, "y": 40.092861509617194, "z": 202.55770226464753, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": -5.845, "front_wheel_angle": -0.29289641281258755, "heading_rate": -0.5583754495913938, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059675.129575}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.845, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059675.129575}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059675.2299168, "x": -88.23536054884153, "y": 40.092861509617194, "z": 202.55770226464753, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": -6.187, "front_wheel_angle": -0.31187654873739146, "heading_rate": -0.6070147073668559, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059675.2296898}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.187, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059675.2296898}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059675.3297982, "x": -88.23536054884153, "y": 40.092861509617194, "z": 202.55770226464753, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": -6.585, "front_wheel_angle": -0.33428420729344643, "heading_rate": -0.6322287098664026, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059675.3296187}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.585, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059675.3296187}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059675.4297457, "x": -88.23536054884153, "y": 40.092861509617194, "z": 202.55770226464753, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": -6.939, "front_wheel_angle": -0.3545162993792736, "heading_rate": -0.6737978799952855, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059675.4296124}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.939, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059675.4296124}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059675.5297656, "x": -88.23536054884153, "y": 40.092861509617194, "z": 202.55770226464753, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": -7.104, "front_wheel_angle": -0.3640472050255921, "heading_rate": -0.6935946476480014, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059675.5295835}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.104, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059675.5295835}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059675.6297078, "x": -88.23533221134201, "y": 40.09286041488677, "z": 202.5420312210835, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": -7.312, "front_wheel_angle": -0.3761559272935587, "heading_rate": -0.7189546535033823, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059675.6295772}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.312, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059675.6295772}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059675.7297091, "x": -88.23533221134201, "y": 40.09286041488677, "z": 202.5420312210835, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": -7.529, "front_wheel_angle": -0.38890314451786573, "heading_rate": -0.7203046386658383, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059675.729575}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.529, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059675.729575}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059675.8297122, "x": -88.23533221134201, "y": 40.09286041488677, "z": 202.5420312210835, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": -7.766, "front_wheel_angle": -0.4029627275290501, "heading_rate": -0.7759808996178221, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059675.829575}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.766, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059675.829575}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059675.929851, "x": -88.23533221134201, "y": 40.09286041488677, "z": 202.5420312210835, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": -8.063, "front_wheel_angle": -0.42079116626490154, "heading_rate": -0.8006445205617765, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059675.9296112}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.063, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059675.9296112}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059676.0298684, "x": -88.23533221134201, "y": 40.09286041488677, "z": 202.5420312210835, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": -8.353, "front_wheel_angle": -0.43843270142529833, "heading_rate": -0.8241807510506531, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059676.0296047}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.353, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059676.0296047}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059676.129744, "x": -88.23530655452717, "y": 40.09285252127331, "z": 202.56126596172572, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": -8.612, "front_wheel_angle": -0.4543910055486245, "heading_rate": -0.87392522969363, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059676.129607}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.612, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059676.129607}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059676.2297804, "x": -88.23530655452717, "y": 40.09285252127331, "z": 202.56126596172572, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": -8.783, "front_wheel_angle": -0.4650355494326491, "heading_rate": -0.8819580436139461, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059676.2296221}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.783, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059676.2296221}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059676.3297749, "x": -88.23530655452717, "y": 40.09285252127331, "z": 202.56126596172572, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": -8.919, "front_wheel_angle": -0.47356461036026837, "heading_rate": -0.8827897263969176, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059676.3296168}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.919, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059676.3296168}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059676.4297676, "x": -88.23530655452717, "y": 40.09285252127331, "z": 202.56126596172572, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": -9.107, "front_wheel_angle": -0.48544928107154556, "heading_rate": -0.9087991030928562, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059676.429582}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.107, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059676.429582}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059676.5297935, "x": -88.23530655452717, "y": 40.09285252127331, "z": 202.56126596172572, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": -9.272, "front_wheel_angle": -0.4959725597838947, "heading_rate": -0.9511251449502591, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059676.529637}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.272, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059676.529637}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059676.6297462, "x": -88.23528682970229, "y": 40.09283798152156, "z": 202.49640996420771, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": -9.364, "front_wheel_angle": -0.5018785198938522, "heading_rate": -0.945297549750949, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059676.629582}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.364, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059676.629582}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059676.7299216, "x": -88.23528682970229, "y": 40.09283798152156, "z": 202.49640996420771, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": -9.42, "front_wheel_angle": -0.505487141573804, "heading_rate": -0.9534019357227317, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059676.7296147}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.42, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059676.7296147}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059676.8297436, "x": -88.23528682970229, "y": 40.09283798152156, "z": 202.49640996420771, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": -9.509, "front_wheel_angle": -0.5112438500297083, "heading_rate": -0.9663978943866312, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059676.829584}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.509, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059676.829584}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059676.9297307, "x": -88.23528682970229, "y": 40.09283798152156, "z": 202.49640996420771, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": -9.67, "front_wheel_angle": -0.5217260535521459, "heading_rate": -0.9902792819223911, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059676.929576}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.67, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059676.929576}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059677.0297732, "x": -88.23528682970229, "y": 40.09283798152156, "z": 202.49640996420771, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": -9.841, "front_wheel_angle": -0.5329579475253724, "heading_rate": -1.0369288999372301, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059677.0295846}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.841, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059677.0295846}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059677.1297984, "x": -88.23527535461905, "y": 40.09281928515365, "z": 202.39394545480934, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": -9.996, "front_wheel_angle": -0.5432290034586835, "heading_rate": -1.0401870208246922, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059677.129614}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.996, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059677.129614}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059677.2298112, "x": -88.23527535461905, "y": 40.09281928515365, "z": 202.39394545480934, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": -10.141, "front_wheel_angle": -0.5529169914840523, "heading_rate": -1.0630957854544925, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059677.2296097}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.141, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059677.2296097}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059677.3298643, "x": -88.23527535461905, "y": 40.09281928515365, "z": 202.39394545480934, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": -10.232, "front_wheel_angle": -0.5590371872225327, "heading_rate": -1.077709395694863, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059677.3296165}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.232, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059677.3296165}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059677.4300172, "x": -88.23527535461905, "y": 40.09281928515365, "z": 202.39394545480934, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9592068162215615, "steering_wheel_angle": -10.357, "front_wheel_angle": -0.5674955578178176, "heading_rate": -1.0781714179757669, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059677.4296534}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.357, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059677.4296534}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059677.529823, "x": -88.23527535461905, "y": 40.09281928515365, "z": 202.39394545480934, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9483428162215617, "steering_wheel_angle": -10.436, "front_wheel_angle": -0.5728725127428796, "heading_rate": -1.0708484214605685, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059677.529607}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.25, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.436, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059677.529607}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059677.6297157, "x": -88.23527414319732, "y": 40.09279919906553, "z": 202.28484041610344, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": -10.459, "front_wheel_angle": -0.5744425660858297, "heading_rate": -1.114996570204019, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059677.6295736}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.459, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059677.6295736}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059677.729802, "x": -88.23527414319732, "y": 40.09279919906553, "z": 202.28484041610344, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": -10.459, "front_wheel_angle": -0.5744425660858297, "heading_rate": -1.114996570204019, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059677.7295823}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.459, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059677.7295823}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059677.8297377, "x": -88.23527414319732, "y": 40.09279919906553, "z": 202.28484041610344, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9483428162215617, "steering_wheel_angle": -10.524, "front_wheel_angle": -0.5788910244378075, "heading_rate": -1.0850525591462628, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059677.8295767}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.25, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.524, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059677.8295767}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059677.929891, "x": -88.23527414319732, "y": 40.09279919906553, "z": 202.28484041610344, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9376068162215616, "steering_wheel_angle": -10.534, "front_wheel_angle": -0.5795768994919425, "heading_rate": -1.066223230547366, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059677.9296484}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.17, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.534, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059677.9296484}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059678.0297008, "x": -88.23527414319732, "y": 40.09279919906553, "z": 202.28484041610344, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9483428162215617, "steering_wheel_angle": -10.56, "front_wheel_angle": -0.5813620537355955, "heading_rate": -1.0909167254491479, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059678.0295718}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.25, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.56, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059678.0295718}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059678.1297731, "x": -88.23528375022427, "y": 40.09278067598641, "z": 202.16764971842744, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9483428162215617, "steering_wheel_angle": -10.598, "front_wheel_angle": -0.5839760290071558, "heading_rate": -1.0971408920108607, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059678.1295767}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.25, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.598, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059678.1295767}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059678.2299845, "x": -88.23528375022427, "y": 40.09278067598641, "z": 202.16764971842744, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9376068162215616, "steering_wheel_angle": -10.7, "front_wheel_angle": -0.5910215652377817, "heading_rate": -1.0930550547462017, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059678.229585}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.17, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.7, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059678.229585}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059678.3297467, "x": -88.23528375022427, "y": 40.09278067598641, "z": 202.16764971842744, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9269988162215617, "steering_wheel_angle": -10.743, "front_wheel_angle": -0.5940045761765337, "heading_rate": -1.079010885273616, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059678.329599}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.09, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.743, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059678.329599}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059678.429724, "x": -88.23528375022427, "y": 40.09278067598641, "z": 202.16764971842744, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9376068162215616, "steering_wheel_angle": -10.813, "front_wheel_angle": -0.598877132472434, "heading_rate": -1.1117116645522558, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059678.4295743}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.17, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.813, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059678.4295743}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059678.5298078, "x": -88.23528375022427, "y": 40.09278067598641, "z": 202.16764971842744, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9269988162215617, "steering_wheel_angle": -10.883, "front_wheel_angle": -0.603770347879955, "heading_rate": -1.1018814397595185, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059678.5296154}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.09, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.883, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059678.5296154}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059678.629832, "x": -88.23530154010768, "y": 40.09276719761921, "z": 202.0850302038321, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9152178162215616, "steering_wheel_angle": -10.988, "front_wheel_angle": -0.6111494881301294, "heading_rate": -1.0947363086759012, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059678.629656}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.988, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059678.629656}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059678.7297869, "x": -88.23530154010768, "y": 40.09276719761921, "z": 202.0850302038321, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9061668162215617, "steering_wheel_angle": -11.101, "front_wheel_angle": -0.6191444996911868, "heading_rate": -1.0939803985294838, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059678.7296154}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.101, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059678.7296154}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059678.8297555, "x": -88.23530154010768, "y": 40.09276719761921, "z": 202.0850302038321, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9217428162215615, "steering_wheel_angle": -11.143, "front_wheel_angle": -0.6221305056424521, "heading_rate": -1.134522486549157, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059678.8295777}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.143, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059678.8295777}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059678.9299471, "x": -88.23530154010768, "y": 40.09276719761921, "z": 202.0850302038321, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9126218162215616, "steering_wheel_angle": -11.15, "front_wheel_angle": -0.6226289401934881, "heading_rate": -1.1160873030173326, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059678.9296246}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.15, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059678.9296246}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059679.0297525, "x": -88.23530154010768, "y": 40.09276719761921, "z": 202.0850302038321, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8972138162215613, "steering_wheel_angle": -11.153, "front_wheel_angle": -0.6228426222958438, "heading_rate": -1.0829247419445727, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059679.0295815}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.86, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.153, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059679.0295815}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059679.1299384, "x": -88.2353236747241, "y": 40.09276061777383, "z": 202.06247441542598, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.887101816221562, "steering_wheel_angle": -11.172, "front_wheel_angle": -0.6241968816340169, "heading_rate": -1.0635147748092637, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059679.1296477}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.78, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.172, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059679.1296477}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059679.2297964, "x": -88.2353236747241, "y": 40.09276061777383, "z": 202.06247441542598, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8921418162215615, "steering_wheel_angle": -11.191, "front_wheel_angle": -0.6255527677039441, "heading_rate": -1.0778447562989955, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059679.2296038}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.191, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059679.2296038}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059679.329895, "x": -88.2353236747241, "y": 40.09276061777383, "z": 202.06247441542598, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8820938162215617, "steering_wheel_angle": -11.204, "front_wheel_angle": -0.6264814195392566, "heading_rate": -1.0573380445409803, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059679.3295918}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.204, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059679.3295918}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059679.4297187, "x": -88.2353236747241, "y": 40.09276061777383, "z": 202.06247441542598, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8796018162215615, "steering_wheel_angle": -11.219, "front_wheel_angle": -0.6275538930749537, "heading_rate": -1.054060422013649, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059679.4295692}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.219, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059679.4295692}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059679.5297134, "x": -88.2353236747241, "y": 40.09276061777383, "z": 202.06247441542598, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8635988162215615, "steering_wheel_angle": -11.277, "front_wheel_angle": -0.6317104423774298, "heading_rate": -1.0261478332709508, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059679.529573}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.59, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059679.529573}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059679.6297054, "x": -88.23534590386456, "y": 40.09276132455345, "z": 202.09534540027414, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8563268162215616, "steering_wheel_angle": -11.334, "front_wheel_angle": -0.6358103942056382, "heading_rate": -1.017704432521882, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059679.6295698}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.53, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.334, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059679.6295698}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059679.730308, "x": -88.23534590386456, "y": 40.09276132455345, "z": 202.09534540027414, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.858742816221562, "steering_wheel_angle": -11.364, "front_wheel_angle": -0.6379743189655555, "heading_rate": -1.0281132137530586, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059679.7296927}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.55, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.364, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059679.7296927}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059679.8300574, "x": -88.23534590386456, "y": 40.09276132455345, "z": 202.09534540027414, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8539188162215616, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -1.0169891838400928, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059679.829652}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.51, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059679.829652}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059679.9297528, "x": -88.23534590386456, "y": 40.09276132455345, "z": 202.09534540027414, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8515188162215614, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -1.011194373675762, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059679.9295723}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.49, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059679.9295723}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059680.029817, "x": -88.23534590386456, "y": 40.09276132455345, "z": 202.09534540027414, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8551218162215615, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -1.0198865889222584, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059680.0295928}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059680.0295928}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059680.1300492, "x": -88.23536493568446, "y": 40.092767952576615, "z": 202.13091522280112, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.858742816221562, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -1.028578804168755, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059680.1296408}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.55, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059680.1296408}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059680.2297318, "x": -88.23536493568446, "y": 40.092767952576615, "z": 202.13091522280112, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8119428162215616, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -0.9126826008821347, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059680.229599}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059680.229599}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059680.3298223, "x": -88.23536493568446, "y": 40.092767952576615, "z": 202.13091522280112, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.843181816221562, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -0.9909125381006033, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059680.3295727}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.42, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059680.3295727}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059680.4297326, "x": -88.23536493568446, "y": 40.092767952576615, "z": 202.13091522280112, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8130738162215616, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -0.9155800059643002, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059680.4296048}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059680.4296048}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059680.5297458, "x": -88.23536493568446, "y": 40.092767952576615, "z": 202.13091522280112, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8256468162215613, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -0.9474514618681208, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059680.529598}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.27, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059680.529598}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059680.6298056, "x": -88.23537888354818, "y": 40.092778473007535, "z": 202.12337564479367, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8210468162215614, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -0.9358618415394587, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059680.6296294}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059680.6296294}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059680.7297316, "x": -88.23537888354818, "y": 40.092778473007535, "z": 202.12337564479367, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8176178162215617, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -0.9271696262929624, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059680.7295763}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059680.7295763}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059680.8297765, "x": -88.23537888354818, "y": 40.092778473007535, "z": 202.12337564479367, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8187588162215613, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -0.9300670313751277, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059680.8296115}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.21, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059680.8296115}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059680.9297466, "x": -88.23537888354818, "y": 40.092778473007535, "z": 202.12337564479367, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8199018162215617, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -0.9329644364572934, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059680.9295752}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059680.9295752}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059681.0296793, "x": -88.23537888354818, "y": 40.092778473007535, "z": 202.12337564479367, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8210468162215614, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -0.9358618415394587, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059681.0295687}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059681.0295687}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059681.1297312, "x": -88.23538708452662, "y": 40.092791720164065, "z": 202.1638187670148, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8256468162215613, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -0.9474514618681208, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059681.1296196}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.27, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059681.1296196}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059681.229711, "x": -88.23538708452662, "y": 40.092791720164065, "z": 202.1638187670148, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8256468162215613, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -0.9474514618681208, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059681.2295685}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.27, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059681.2295685}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059681.329699, "x": -88.23538708452662, "y": 40.092791720164065, "z": 202.1638187670148, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8291178162215616, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -0.9561436771146172, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059681.329594}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059681.329594}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059681.4297662, "x": -88.23538708452662, "y": 40.092791720164065, "z": 202.1638187670148, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.840817816221562, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -0.9851177279362723, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059681.4296057}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059681.4296057}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059681.5298932, "x": -88.23538708452662, "y": 40.092791720164065, "z": 202.1638187670148, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8291178162215616, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -0.9561436771146172, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059681.52964}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059681.52964}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059681.629817, "x": -88.2353892497824, "y": 40.09280655801486, "z": 202.12322918614427, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8384618162215616, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -0.9793229177719415, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059681.6296148}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059681.6296148}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059681.729767, "x": -88.2353892497824, "y": 40.09280655801486, "z": 202.12322918614427, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8349428162215617, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -0.9706307025254448, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059681.729596}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.35, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059681.729596}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059681.829941, "x": -88.2353892497824, "y": 40.09280655801486, "z": 202.12322918614427, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8455538162215617, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -0.9967073482649343, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059681.8296137}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059681.8296137}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059681.9297764, "x": -88.2353892497824, "y": 40.09280655801486, "z": 202.12322918614427, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8467428162215613, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -0.9996047533470999, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059681.9296048}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.45, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059681.9296048}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059682.0296779, "x": -88.2353892497824, "y": 40.09280655801486, "z": 202.12322918614427, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8479338162215617, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -1.0025021584292655, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059682.0295649}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059682.0295649}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059682.129695, "x": -88.23538488275928, "y": 40.09282140843407, "z": 202.18038596439695, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8443668162215614, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -0.993809943182769, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059682.1295674}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059682.1295674}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059682.2299862, "x": -88.23538488275928, "y": 40.09282140843407, "z": 202.18038596439695, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.858742816221562, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -1.028578804168755, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059682.2296648}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.55, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059682.2296648}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059682.3297746, "x": -88.23538488275928, "y": 40.09282140843407, "z": 202.18038596439695, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8479338162215617, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -1.0025021584292655, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059682.3295796}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059682.3295796}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059682.429826, "x": -88.23538488275928, "y": 40.09282140843407, "z": 202.18038596439695, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.858742816221562, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -1.028578804168755, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059682.4296088}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.55, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059682.4296088}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059682.5297062, "x": -88.23538488275928, "y": 40.09282140843407, "z": 202.18038596439695, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8599538162215614, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -1.0314762092509204, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059682.5295684}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059682.5295684}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059682.6297414, "x": -88.23537365048037, "y": 40.092834492450635, "z": 202.27143587242455, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8660388162215615, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -1.045963234661748, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059682.6296027}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059682.6296027}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059682.729736, "x": -88.23537365048037, "y": 40.092834492450635, "z": 202.27143587242455, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8660388162215615, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -1.045963234661748, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059682.7295992}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059682.7295992}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059682.8297095, "x": -88.23537365048037, "y": 40.092834492450635, "z": 202.27143587242455, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8660388162215615, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -1.045963234661748, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059682.8295934}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059682.8295934}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059682.9296718, "x": -88.23537365048037, "y": 40.092834492450635, "z": 202.27143587242455, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8599538162215614, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -1.0314762092509204, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059682.9295633}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059682.9295633}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059683.0297334, "x": -88.23537365048037, "y": 40.092834492450635, "z": 202.27143587242455, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8783588162215614, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -1.0749372854834032, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059683.0295677}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.71, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059683.0295677}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059683.1297278, "x": -88.23535650789101, "y": 40.09284408976559, "z": 202.37703061813727, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8734068162215616, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -1.063347665154741, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059683.129576}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059683.129576}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059683.2297428, "x": -88.23535650789101, "y": 40.09284408976559, "z": 202.37703061813727, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8709428162215618, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -1.05755285499041, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059683.2296033}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059683.2296033}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059683.3298776, "x": -88.23535650789101, "y": 40.09284408976559, "z": 202.37703061813727, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.887101816221562, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -1.0952191210585616, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059683.329634}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.78, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059683.329634}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059683.4296892, "x": -88.23535650789101, "y": 40.09284408976559, "z": 202.37703061813727, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8783588162215614, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -1.0749372854834032, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059683.429563}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.71, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059683.429563}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059683.529751, "x": -88.23535650789101, "y": 40.09284408976559, "z": 202.37703061813727, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8972138162215613, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -1.1183983617158857, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059683.5296047}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.86, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059683.5296047}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059683.6296687, "x": -88.23533535093533, "y": 40.09284822587267, "z": 202.47229753782895, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8721738162215615, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -1.0604502600725756, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059683.6295605}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059683.6295605}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059683.7298687, "x": -88.23533535093533, "y": 40.09284822587267, "z": 202.47229753782895, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8997618162215613, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -1.1241931718802167, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059683.7296364}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.88, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059683.7296364}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059683.8297307, "x": -88.23533535093533, "y": 40.09284822587267, "z": 202.47229753782895, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8721738162215615, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -1.0604502600725756, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059683.8295808}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059683.8295808}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059683.9297256, "x": -88.23533535093533, "y": 40.09284822587267, "z": 202.47229753782895, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9087428162215616, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -1.1444750074553753, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059683.9295974}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059683.9295974}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059684.0297077, "x": -88.23533535093533, "y": 40.09284822587267, "z": 202.47229753782895, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8896178162215618, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -1.1010139312228926, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059684.0296018}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.8, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059684.0296018}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059684.129893, "x": -88.23531308051874, "y": 40.09284575748766, "z": 202.55662380062648, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9100338162215618, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -1.1473724125375406, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059684.1295755}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.96, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059684.1295755}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059684.2297342, "x": -88.23531308051874, "y": 40.09284575748766, "z": 202.55662380062648, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8896178162215618, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -1.1010139312228926, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059684.2295938}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.8, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059684.2295938}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059684.3297672, "x": -88.23531308051874, "y": 40.09284575748766, "z": 202.55662380062648, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9023178162215615, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -1.1299879820445478, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059684.3296072}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.9, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059684.3296072}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059684.4300096, "x": -88.23531308051874, "y": 40.09284575748766, "z": 202.55662380062648, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8946738162215615, "steering_wheel_angle": -11.361, "front_wheel_angle": -0.6377577375440673, "heading_rate": -1.1115965619482147, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059684.4296088}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.84, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059684.4296088}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059684.5296946, "x": -88.23531308051874, "y": 40.09284575748766, "z": 202.55662380062648, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8984868162215616, "steering_wheel_angle": -11.346, "front_wheel_angle": -0.636675460743374, "heading_rate": -1.1177483356907667, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059684.5295696}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.346, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059684.5295696}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059684.6300395, "x": -88.23529344998246, "y": 40.09283647316053, "z": 202.65716749553064, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8858468162215614, "steering_wheel_angle": -11.256, "front_wheel_angle": -0.6302037077825869, "heading_rate": -1.074194900771483, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059684.6295996}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.256, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059684.6295996}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059684.7298696, "x": -88.23529344998246, "y": 40.09283647316053, "z": 202.65716749553064, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8758788162215616, "steering_wheel_angle": -10.891, "front_wheel_angle": -0.6043308997721059, "heading_rate": -0.9953107489011702, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059684.729631}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.891, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059684.729631}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059684.8298032, "x": -88.23529344998246, "y": 40.09283647316053, "z": 202.65716749553064, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8709428162215618, "steering_wheel_angle": -10.38, "front_wheel_angle": -0.5690584804922979, "heading_rate": -0.9119881708197913, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059684.8295865}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.38, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059684.8295865}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059684.9297352, "x": -88.23529344998246, "y": 40.09283647316053, "z": 202.65716749553064, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9048818162215615, "steering_wheel_angle": -9.81, "front_wheel_angle": -0.5309140952945489, "heading_rate": -0.899066660189091, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059684.9295979}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.81, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059684.9295979}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059685.0297341, "x": -88.23529344998246, "y": 40.09283647316053, "z": 202.65716749553064, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8934068162215616, "steering_wheel_angle": -9.063, "front_wheel_angle": -0.482657796126196, "heading_rate": -0.7839436794855995, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059685.0296001}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.063, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059685.0296001}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059685.1302524, "x": -88.23527937970736, "y": 40.092822465309766, "z": 202.6985577035208, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8758788162215616, "steering_wheel_angle": -8.192, "front_wheel_angle": -0.42860959036237295, "heading_rate": -0.6586350703856415, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059685.1296985}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.192, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059685.1296985}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059685.229697, "x": -88.23527937970736, "y": 40.092822465309766, "z": 202.6985577035208, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8672618162215615, "steering_wheel_angle": -7.369, "front_wheel_angle": -0.37949281811457664, "heading_rate": -0.5639631197028476, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059685.2295692}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.369, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059685.2295692}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059685.329796, "x": -88.23527937970736, "y": 40.092822465309766, "z": 202.6985577035208, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.858742816221562, "steering_wheel_angle": -6.516, "front_wheel_angle": -0.3303741717041015, "heading_rate": -0.47556547704218155, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059685.3295877}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.55, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.516, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059685.3295877}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059685.4297328, "x": -88.23527937970736, "y": 40.092822465309766, "z": 202.6985577035208, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.858742816221562, "steering_wheel_angle": -5.733, "front_wheel_angle": -0.2867341001096568, "heading_rate": -0.4088872083771075, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059685.429572}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.55, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.733, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059685.429572}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059685.5297759, "x": -88.23527937970736, "y": 40.092822465309766, "z": 202.6985577035208, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8734068162215616, "steering_wheel_angle": -4.922, "front_wheel_angle": -0.2428624658152133, "heading_rate": -0.35517675942518095, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059685.5295799}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.922, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059685.5295799}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059685.6299117, "x": -88.23526949167619, "y": 40.09280756075712, "z": 202.66465116661752, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8635988162215615, "steering_wheel_angle": -4.106, "front_wheel_angle": -0.19997068556282588, "heading_rate": -0.28422635347313907, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059685.629635}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.59, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.106, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059685.629635}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059685.7297926, "x": -88.23526949167619, "y": 40.09280756075712, "z": 202.66465116661752, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8551218162215615, "steering_wheel_angle": -3.294, "front_wheel_angle": -0.15843402897011055, "heading_rate": -0.2196880279562695, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059685.72962}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.294, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059685.72962}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059685.8297813, "x": -88.23526949167619, "y": 40.09280756075712, "z": 202.66465116661752, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8479338162215617, "steering_wheel_angle": -2.525, "front_wheel_angle": -0.12007081558394446, "heading_rate": -0.16306761455492247, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059685.8296022}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.525, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059685.8296022}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059685.9297907, "x": -88.23526949167619, "y": 40.09280756075712, "z": 202.66465116661752, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.874641816221562, "steering_wheel_angle": -1.708, "front_wheel_angle": -0.08027669135237406, "heading_rate": -0.11564627218804734, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059685.9296062}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.68, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.708, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059685.9296062}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059686.0297232, "x": -88.23526949167619, "y": 40.09280756075712, "z": 202.66465116661752, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8623818162215615, "steering_wheel_angle": -0.893, "front_wheel_angle": -0.04150160671501501, "heading_rate": -0.0580707469988875, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059686.0295663}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.893, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059686.0295663}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059686.1297572, "x": -88.23526073804608, "y": 40.0927927684976, "z": 202.60716253442132, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8503218162215616, "steering_wheel_angle": -0.143, "front_wheel_angle": -0.006579511737334867, "heading_rate": -0.008944152832362011, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059686.1296158}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.143, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059686.1296158}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059686.2297895, "x": -88.23526073804608, "y": 40.0927927684976, "z": 202.60716253442132, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8623818162215615, "steering_wheel_angle": 0.589, "front_wheel_angle": 0.027261345335914174, "heading_rate": 0.038132734593557614, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059686.2295816}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.589, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059686.2295816}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059686.3297765, "x": -88.23526073804608, "y": 40.0927927684976, "z": 202.60716253442132, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8734068162215616, "steering_wheel_angle": 1.311, "front_wheel_angle": 0.061277681018183976, "heading_rate": 0.08795742011915725, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059686.3295786}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.311, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059686.3295786}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059686.4299152, "x": -88.23526073804608, "y": 40.0927927684976, "z": 202.60716253442132, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8575338162215616, "steering_wheel_angle": 2.032, "front_wheel_angle": 0.09594360885971745, "heading_rate": 0.13308061593870416, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059686.42963}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.54, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.032, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059686.42963}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059686.5297425, "x": -88.23526073804608, "y": 40.0927927684976, "z": 202.60716253442132, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8599538162215614, "steering_wheel_angle": 2.703, "front_wheel_angle": 0.12887012419245417, "heading_rate": 0.18020872874446714, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059686.5295794}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.703, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059686.5295794}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059686.6297386, "x": -88.23525144559136, "y": 40.092778721778544, "z": 202.61156806915395, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8672618162215615, "steering_wheel_angle": 3.359, "front_wheel_angle": 0.1617190849471584, "heading_rate": 0.23069554042236048, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059686.6295884}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.359, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059686.6295884}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059686.729753, "x": -88.23525144559136, "y": 40.092778721778544, "z": 202.61156806915395, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8575338162215616, "steering_wheel_angle": 4.066, "front_wheel_angle": 0.19789856421873972, "heading_rate": 0.2772859559992856, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059686.7295942}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.54, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.066, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059686.7295942}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059686.8297265, "x": -88.23525144559136, "y": 40.092778721778544, "z": 202.61156806915395, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.864817816221562, "steering_wheel_angle": 4.752, "front_wheel_angle": 0.23382680878165896, "heading_rate": 0.33494569956444825, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059686.8295934}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.6, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.752, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059686.8295934}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059686.9299839, "x": -88.23525144559136, "y": 40.092778721778544, "z": 202.61156806915395, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8611668162215613, "steering_wheel_angle": 5.433, "front_wheel_angle": 0.2703540854108328, "heading_rate": 0.386479525816933, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059686.9296367}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.433, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059686.9296367}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059687.0297244, "x": -88.23525144559136, "y": 40.092778721778544, "z": 202.61156806915395, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8623818162215615, "steering_wheel_angle": 6.058, "front_wheel_angle": 0.3046881577092787, "heading_rate": 0.4397813382420396, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059687.029569}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.058, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059687.029569}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059687.1298902, "x": -88.2352397689581, "y": 40.092766757610526, "z": 202.61316236313405, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8623818162215615, "steering_wheel_angle": 6.675, "front_wheel_angle": 0.33940050736877236, "heading_rate": 0.4937358593577644, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059687.1295962}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.675, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059687.1295962}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059687.230063, "x": -88.2352397689581, "y": 40.092766757610526, "z": 202.61316236313405, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8611668162215613, "steering_wheel_angle": 7.272, "front_wheel_angle": 0.3738190703476672, "heading_rate": 0.5470234355002992, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059687.229694}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.272, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059687.229694}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059687.3297908, "x": -88.2352397689581, "y": 40.092766757610526, "z": 202.61316236313405, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8623818162215615, "steering_wheel_angle": 7.786, "front_wheel_angle": 0.40415589564807336, "heading_rate": 0.5981126260826009, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059687.3295848}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.786, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059687.3295848}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059687.4297562, "x": -88.2352397689581, "y": 40.092766757610526, "z": 202.61316236313405, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8623818162215615, "steering_wheel_angle": 8.361, "front_wheel_angle": 0.4389227213696016, "heading_rate": 0.6565176753814582, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059687.4296062}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059687.4296062}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059687.5297668, "x": -88.2352397689581, "y": 40.092766757610526, "z": 202.61316236313405, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.864817816221562, "steering_wheel_angle": 8.891, "front_wheel_angle": 0.47180398561045156, "heading_rate": 0.7175214112842084, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059687.5295815}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.6, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.891, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059687.5295815}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059687.6297476, "x": -88.2352254370999, "y": 40.092758285058345, "z": 202.6147130873331, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8623818162215615, "steering_wheel_angle": 9.294, "front_wheel_angle": 0.4973823273497391, "heading_rate": 0.7592235048972108, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059687.629575}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.294, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059687.629575}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059687.729767, "x": -88.2352254370999, "y": 40.092758285058345, "z": 202.6147130873331, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8527178162215616, "steering_wheel_angle": 9.592, "front_wheel_angle": 0.5166366205367241, "heading_rate": 0.7767052494923705, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059687.729599}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.592, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059687.729599}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059687.8298273, "x": -88.2352254370999, "y": 40.092758285058345, "z": 202.6147130873331, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8611668162215613, "steering_wheel_angle": 9.972, "front_wheel_angle": 0.5416329480127606, "heading_rate": 0.8390218073977844, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059687.829611}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.972, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059687.829611}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059687.9298134, "x": -88.2352254370999, "y": 40.092758285058345, "z": 202.6147130873331, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8563268162215616, "steering_wheel_angle": 10.27, "front_wheel_angle": 0.5616021788823364, "heading_rate": 0.8675853661807565, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059687.9296012}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.53, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.27, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059687.9296012}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059688.0297413, "x": -88.2352254370999, "y": 40.092758285058345, "z": 202.6147130873331, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8503218162215616, "steering_wheel_angle": 10.465, "front_wheel_angle": 0.5748524893317803, "heading_rate": 0.8806521371710104, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059688.029592}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.465, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059688.029592}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059688.1298172, "x": -88.23520943863653, "y": 40.0927543501826, "z": 202.61023210097576, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8467428162215613, "steering_wheel_angle": 10.693, "front_wheel_angle": 0.5905366833085389, "heading_rate": 0.9033787348503393, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059688.129595}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.45, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.693, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059688.129595}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059688.2298133, "x": -88.23520943863653, "y": 40.0927543501826, "z": 202.61023210097576, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8443668162215614, "steering_wheel_angle": 10.903, "front_wheel_angle": 0.6051722409026273, "heading_rate": 0.926846176580433, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059688.2296088}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.903, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059688.2296088}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059688.330042, "x": -88.23520943863653, "y": 40.0927543501826, "z": 202.61023210097576, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8396388162215613, "steering_wheel_angle": 10.942, "front_wheel_angle": 0.6079108688613916, "heading_rate": 0.9214096088269647, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059688.3296971}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.39, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.942, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059688.3296971}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059688.4297287, "x": -88.23520943863653, "y": 40.0927543501826, "z": 202.61023210097576, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8337738162215613, "steering_wheel_angle": 10.965, "front_wheel_angle": 0.6095290318914761, "heading_rate": 0.9109563787160327, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059688.429595}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.965, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059688.429595}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059688.5296972, "x": -88.23520943863653, "y": 40.0927543501826, "z": 202.61023210097576, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.824493816221562, "steering_wheel_angle": 10.967, "front_wheel_angle": 0.6096698499547231, "heading_rate": 0.8894038349706122, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059688.5295637}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.26, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.967, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059688.5295637}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059688.6298175, "x": -88.23519386222434, "y": 40.09275527138806, "z": 202.57685592707892, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.822193816221562, "steering_wheel_angle": 11.018, "front_wheel_angle": 0.6132665892107312, "heading_rate": 0.8907371087821577, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059688.6295803}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.018, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059688.6295803}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059688.7300239, "x": -88.23519386222434, "y": 40.09275527138806, "z": 202.57685592707892, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8142068162215614, "steering_wheel_angle": 11.039, "front_wheel_angle": 0.6147509029608098, "heading_rate": 0.8742440662450718, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059688.7296267}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.17, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.039, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059688.7296267}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059688.8297648, "x": -88.23519386222434, "y": 40.09275527138806, "z": 202.57685592707892, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8108138162215615, "steering_wheel_angle": 11.039, "front_wheel_angle": 0.6147509029608098, "heading_rate": 0.8659704630944877, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059688.8296082}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.14, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.039, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059688.8296082}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059688.9297771, "x": -88.23519386222434, "y": 40.09275527138806, "z": 202.57685592707892, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8108138162215615, "steering_wheel_angle": 11.036, "front_wheel_angle": 0.6145387396533585, "heading_rate": 0.8655805759628025, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059688.9295936}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.14, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.036, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059688.9295936}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059689.029696, "x": -88.23519386222434, "y": 40.09275527138806, "z": 202.57685592707892, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8153418162215615, "steering_wheel_angle": 11.034, "front_wheel_angle": 0.6143973194120432, "heading_rate": 0.876343950762327, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059689.0295608}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059689.0295608}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059689.1297474, "x": -88.23518064930461, "y": 40.0927599833973, "z": 202.53138406223604, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7725588162215615, "steering_wheel_angle": 11.033, "front_wheel_angle": 0.6143266158780261, "heading_rate": 0.7687524044959375, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059689.129598}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.79, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.033, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059689.129598}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059689.2297974, "x": -88.23518064930461, "y": 40.0927599833973, "z": 202.53138406223604, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7875668162215614, "steering_wheel_angle": 11.033, "front_wheel_angle": 0.6143266158780261, "heading_rate": 0.807327793968852, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059689.2295933}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.033, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059689.2295933}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059689.3297336, "x": -88.23518064930461, "y": 40.0927599833973, "z": 202.53138406223604, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8007428162215615, "steering_wheel_angle": 11.033, "front_wheel_angle": 0.6143266158780261, "heading_rate": 0.8403924135170642, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059689.329578}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.033, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059689.329578}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059689.4299972, "x": -88.23518064930461, "y": 40.0927599833973, "z": 202.53138406223604, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7704468162215616, "steering_wheel_angle": 11.031, "front_wheel_angle": 0.6141852219791838, "heading_rate": 0.7630125419632635, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059689.4296353}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.031, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059689.4296353}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059689.529829, "x": -88.23518064930461, "y": 40.0927599833973, "z": 202.53138406223604, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7810868162215616, "steering_wheel_angle": 11.025, "front_wheel_angle": 0.6137611455773521, "heading_rate": 0.7898464923128472, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059689.5296085}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059689.5296085}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059689.6299307, "x": -88.23517073176448, "y": 40.09276671588639, "z": 202.54832677202455, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7800138162215617, "steering_wheel_angle": 11.022, "front_wheel_angle": 0.6135491665642899, "heading_rate": 0.7867400971379804, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059689.6296082}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.86, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.022, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059689.6296082}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059689.729743, "x": -88.23517073176448, "y": 40.09276671588639, "z": 202.54832677202455, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7800138162215617, "steering_wheel_angle": 11.022, "front_wheel_angle": 0.6135491665642899, "heading_rate": 0.7867400971379804, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059689.7295756}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.86, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.022, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059689.7295756}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059689.8297274, "x": -88.23517073176448, "y": 40.09276671588639, "z": 202.54832677202455, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7919268162215616, "steering_wheel_angle": 11.022, "front_wheel_angle": 0.6135491665642899, "heading_rate": 0.8169993316432875, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059689.8295665}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.022, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059689.8295665}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059689.929719, "x": -88.23517073176448, "y": 40.09276671588639, "z": 202.54832677202455, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7757418162215615, "steering_wheel_angle": 11.022, "front_wheel_angle": 0.6135491665642899, "heading_rate": 0.7757367391360507, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059689.9295685}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.022, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059689.9295685}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059690.0297112, "x": -88.23517073176448, "y": 40.09276671588639, "z": 202.54832677202455, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7952178162215615, "steering_wheel_angle": 11.022, "front_wheel_angle": 0.6135491665642899, "heading_rate": 0.8252518501447349, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059690.0295775}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.022, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059690.0295775}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059690.1297324, "x": -88.23516391993161, "y": 40.09277519160468, "z": 202.57880877809518, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7875668162215614, "steering_wheel_angle": 10.986, "front_wheel_angle": 0.6110084876102121, "heading_rate": 0.8016537717321143, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059690.1295621}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.986, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059690.1295621}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059690.2298696, "x": -88.23516391993161, "y": 40.09277519160468, "z": 202.57880877809518, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8040818162215615, "steering_wheel_angle": 10.716, "front_wheel_angle": 0.5921306273246212, "heading_rate": 0.8092770460607355, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059690.2296383}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.716, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059690.2296383}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059690.329828, "x": -88.23516391993161, "y": 40.09277519160468, "z": 202.57880877809518, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7963188162215618, "steering_wheel_angle": 10.358, "front_wheel_angle": 0.5675634681284413, "heading_rate": 0.7496032828066922, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059690.329601}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.358, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059690.329601}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059690.429783, "x": -88.23516391993161, "y": 40.09277519160468, "z": 202.57880877809518, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.801853816221562, "steering_wheel_angle": 10.103, "front_wheel_angle": 0.5503705239711425, "heading_rate": 0.7334618378771515, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059690.4295928}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.103, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059690.4295928}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059690.5297859, "x": -88.23516391993161, "y": 40.09277519160468, "z": 202.57880877809518, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8108138162215615, "steering_wheel_angle": 9.933, "front_wheel_angle": 0.5390438335309855, "heading_rate": 0.7336446070275647, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059690.5296}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.14, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.933, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059690.5296}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059690.6297755, "x": -88.23516003196498, "y": 40.092785632149614, "z": 202.60438061393572, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8108138162215615, "steering_wheel_angle": 9.676, "front_wheel_angle": 0.5221184200487731, "heading_rate": 0.7057372570697255, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059690.6295972}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.14, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059690.6295972}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059690.7297566, "x": -88.23516003196498, "y": 40.092785632149614, "z": 202.60438061393572, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8187588162215613, "steering_wheel_angle": 9.474, "front_wheel_angle": 0.508976797724446, "heading_rate": 0.6996999249899162, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059690.729597}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.21, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.474, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059690.729597}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059690.8297179, "x": -88.23516003196498, "y": 40.092785632149614, "z": 202.60438061393572, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.822193816221562, "steering_wheel_angle": 9.446, "front_wheel_angle": 0.5071661261978605, "heading_rate": 0.7032370028232542, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059690.8295894}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.446, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059690.8295894}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059690.9297729, "x": -88.23516003196498, "y": 40.092785632149614, "z": 202.60438061393572, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8302788162215617, "steering_wheel_angle": 9.453, "front_wheel_angle": 0.5076185472732068, "heading_rate": 0.7191961564069096, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059690.9295928}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.453, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059690.9295928}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059691.0300097, "x": -88.23516003196498, "y": 40.092785632149614, "z": 202.60438061393572, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8384618162215616, "steering_wheel_angle": 9.453, "front_wheel_angle": 0.5076185472732068, "heading_rate": 0.7344057427961797, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059691.029651}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.453, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059691.029651}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059691.129779, "x": -88.2351596361275, "y": 40.09279749262052, "z": 202.63929769148393, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8349428162215617, "steering_wheel_angle": 9.461, "front_wheel_angle": 0.5081358012692266, "heading_rate": 0.728773903566429, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059691.1296008}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.35, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.461, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059691.1296008}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059691.2298455, "x": -88.2351596361275, "y": 40.09279749262052, "z": 202.63929769148393, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8539188162215616, "steering_wheel_angle": 9.475, "front_wheel_angle": 0.5090415133100508, "heading_rate": 0.7652088059607537, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059691.229613}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.51, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.475, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059691.229613}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059691.329772, "x": -88.2351596361275, "y": 40.09279749262052, "z": 202.63929769148393, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8575338162215616, "steering_wheel_angle": 9.49, "front_wheel_angle": 0.5100126514280879, "heading_rate": 0.7735111924269441, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059691.329615}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.54, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.49, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059691.329615}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059691.429748, "x": -88.2351596361275, "y": 40.09279749262052, "z": 202.63929769148393, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8672618162215615, "steering_wheel_angle": 9.537, "front_wheel_angle": 0.5130604763118867, "heading_rate": 0.7966597114219496, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059691.429591}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.537, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059691.429591}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059691.5298069, "x": -88.2351596361275, "y": 40.09279749262052, "z": 202.63929769148393, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.858742816221562, "steering_wheel_angle": 9.563, "front_wheel_angle": 0.5147497300187599, "heading_rate": 0.7843436703615647, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059691.529625}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.55, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059691.529625}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059691.629723, "x": -88.23516429447203, "y": 40.09280989482304, "z": 202.6403575105071, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8833428162215613, "steering_wheel_angle": 9.561, "front_wheel_angle": 0.5146197056155634, "heading_rate": 0.8282806662603673, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059691.6295915}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.75, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.561, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059691.6295915}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059691.7296886, "x": -88.23516429447203, "y": 40.09280989482304, "z": 202.6403575105071, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8709428162215618, "steering_wheel_angle": 9.582, "front_wheel_angle": 0.5159856435059906, "heading_rate": 0.8087653663382767, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059691.7295606}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.582, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059691.7295606}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059691.8300471, "x": -88.23516429447203, "y": 40.09280989482304, "z": 202.6403575105071, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8734068162215616, "steering_wheel_angle": 9.682, "front_wheel_angle": 0.5225109116617636, "heading_rate": 0.8256076352756523, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059691.829615}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.682, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059691.829615}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059691.929854, "x": -88.23516429447203, "y": 40.09280989482304, "z": 202.6403575105071, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8808468162215615, "steering_wheel_angle": 9.862, "front_wheel_angle": 0.5343444401638869, "heading_rate": 0.8622242116734998, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059691.9296095}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.73, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.862, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059691.9296095}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059692.029981, "x": -88.23516429447203, "y": 40.09280989482304, "z": 202.6403575105071, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8734068162215616, "steering_wheel_angle": 10.101, "front_wheel_angle": 0.5502366487124115, "heading_rate": 0.8794106541697273, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059692.029652}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.101, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059692.029652}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059692.1297858, "x": -88.23517430048065, "y": 40.092821115649805, "z": 202.6348761153465, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.887101816221562, "steering_wheel_angle": 10.347, "front_wheel_angle": 0.5668166685524119, "heading_rate": 0.9398121098877773, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059692.129583}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.78, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.347, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059692.129583}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059692.229873, "x": -88.23517430048065, "y": 40.092821115649805, "z": 202.6348761153465, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.887101816221562, "steering_wheel_angle": 10.575, "front_wheel_angle": 0.5823931887752121, "heading_rate": 0.9724556188740524, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059692.2295952}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.78, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.575, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059692.2295952}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059692.3297482, "x": -88.23517430048065, "y": 40.092821115649805, "z": 202.6348761153465, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8820938162215617, "steering_wheel_angle": 10.779, "front_wheel_angle": 0.5965078981685672, "heading_rate": 0.9920093603843574, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059692.329573}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.779, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059692.329573}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059692.4297345, "x": -88.23517430048065, "y": 40.092821115649805, "z": 202.6348761153465, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8883588162215617, "steering_wheel_angle": 10.935, "front_wheel_angle": 0.6074188381526917, "heading_rate": 1.0290497631904574, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059692.4295907}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.79, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.935, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059692.4295907}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059692.529802, "x": -88.23517430048065, "y": 40.092821115649805, "z": 202.6348761153465, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8908788162215617, "steering_wheel_angle": 11.003, "front_wheel_angle": 0.6122075475416819, "heading_rate": 1.0450857568477696, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059692.5296068}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.003, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059692.5296068}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059692.629996, "x": -88.23518844504925, "y": 40.09282889538657, "z": 202.58121342176992, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8783588162215614, "steering_wheel_angle": 11.007, "front_wheel_angle": 0.6124898624975517, "heading_rate": 1.0182666862439502, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059692.6296146}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.71, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.007, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059692.6296146}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059692.7296968, "x": -88.23518844504925, "y": 40.09282889538657, "z": 202.58121342176992, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8997618162215613, "steering_wheel_angle": 11.007, "front_wheel_angle": 0.6124898624975517, "heading_rate": 1.0649258066378777, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059692.7295604}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.88, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.007, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059692.7295604}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059692.829754, "x": -88.23518844504925, "y": 40.09282889538657, "z": 202.58121342176992, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8783588162215614, "steering_wheel_angle": 11.007, "front_wheel_angle": 0.6124898624975517, "heading_rate": 1.0182666862439502, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059692.8295712}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.71, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.007, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059692.8295712}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059692.9297843, "x": -88.23518844504925, "y": 40.09282889538657, "z": 202.58121342176992, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8934068162215616, "steering_wheel_angle": 11.007, "front_wheel_angle": 0.6124898624975517, "heading_rate": 1.0512025359337813, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059692.929597}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.007, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059692.929597}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059693.029713, "x": -88.23518844504925, "y": 40.09282889538657, "z": 202.58121342176992, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8833428162215613, "steering_wheel_angle": 11.007, "front_wheel_angle": 0.6124898624975517, "heading_rate": 1.0292453028072273, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059693.0295641}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.75, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.007, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059693.0295641}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059693.1299803, "x": -88.2352050456186, "y": 40.092831711548584, "z": 202.54956785358482, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8972138162215613, "steering_wheel_angle": 11.007, "front_wheel_angle": 0.6124898624975517, "heading_rate": 1.0594364983562392, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059693.1296527}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.86, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.007, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059693.1296527}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059693.2297137, "x": -88.2352050456186, "y": 40.092831711548584, "z": 202.54956785358482, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8883588162215617, "steering_wheel_angle": 11.007, "front_wheel_angle": 0.6124898624975517, "heading_rate": 1.0402239193705043, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059693.229567}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.79, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.007, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059693.229567}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059693.3298397, "x": -88.2352050456186, "y": 40.092831711548584, "z": 202.54956785358482, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8934068162215616, "steering_wheel_angle": 11.007, "front_wheel_angle": 0.6124898624975517, "heading_rate": 1.0512025359337813, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059693.3295813}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.007, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059693.3295813}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059693.4297154, "x": -88.2352050456186, "y": 40.092831711548584, "z": 202.54956785358482, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8934068162215616, "steering_wheel_angle": 11.007, "front_wheel_angle": 0.6124898624975517, "heading_rate": 1.0512025359337813, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059693.4295616}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.007, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059693.4295616}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059693.529949, "x": -88.2352050456186, "y": 40.092831711548584, "z": 202.54956785358482, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8934068162215616, "steering_wheel_angle": 11.007, "front_wheel_angle": 0.6124898624975517, "heading_rate": 1.0512025359337813, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059693.5296402}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.007, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059693.5296402}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059693.6297941, "x": -88.235222252527, "y": 40.09282924105298, "z": 202.55153237508802, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8972138162215613, "steering_wheel_angle": 11.007, "front_wheel_angle": 0.6124898624975517, "heading_rate": 1.0594364983562392, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059693.6296108}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.86, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.007, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059693.6296108}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059693.7297099, "x": -88.235222252527, "y": 40.09282924105298, "z": 202.55153237508802, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8997618162215613, "steering_wheel_angle": 11.007, "front_wheel_angle": 0.6124898624975517, "heading_rate": 1.0649258066378777, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059693.7295656}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.88, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.007, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059693.7295656}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059693.8297305, "x": -88.235222252527, "y": 40.09282924105298, "z": 202.55153237508802, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9074538162215617, "steering_wheel_angle": 11.007, "front_wheel_angle": 0.6124898624975517, "heading_rate": 1.0813937314827933, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059693.829564}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.94, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.007, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059693.829564}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059693.9297523, "x": -88.235222252527, "y": 40.09282924105298, "z": 202.55153237508802, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9230538162215614, "steering_wheel_angle": 11.007, "front_wheel_angle": 0.6124898624975517, "heading_rate": 1.1143295811726244, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059693.9295998}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.007, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059693.9295998}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059694.0296776, "x": -88.235222252527, "y": 40.09282924105298, "z": 202.55153237508802, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9087428162215616, "steering_wheel_angle": 11.007, "front_wheel_angle": 0.6124898624975517, "heading_rate": 1.0841383856236126, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059694.0295541}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.007, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059694.0295541}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059694.1297588, "x": -88.23523722658771, "y": 40.092821647980166, "z": 202.5281014541492, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9230538162215614, "steering_wheel_angle": 11.007, "front_wheel_angle": 0.6124898624975517, "heading_rate": 1.1143295811726244, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059694.129604}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.007, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059694.129604}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059694.2299712, "x": -88.23523722658771, "y": 40.092821647980166, "z": 202.5281014541492, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9230538162215614, "steering_wheel_angle": 11.007, "front_wheel_angle": 0.6124898624975517, "heading_rate": 1.1143295811726244, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059694.2296436}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.007, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059694.2296436}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059694.3297217, "x": -88.23523722658771, "y": 40.092821647980166, "z": 202.5281014541492, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9126218162215616, "steering_wheel_angle": 11.007, "front_wheel_angle": 0.6124898624975517, "heading_rate": 1.0923723480460703, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059694.3295667}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.007, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059694.3295667}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059694.429826, "x": -88.23523722658771, "y": 40.092821647980166, "z": 202.5281014541492, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9269988162215617, "steering_wheel_angle": 11.007, "front_wheel_angle": 0.6124898624975517, "heading_rate": 1.1225635435950823, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059694.4296029}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.09, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.007, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059694.4296029}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059694.530139, "x": -88.23523722658771, "y": 40.092821647980166, "z": 202.5281014541492, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9336138162215617, "steering_wheel_angle": 11.007, "front_wheel_angle": 0.6124898624975517, "heading_rate": 1.1362868142991787, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059694.5297122}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.14, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.007, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059694.5297122}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059694.6297643, "x": -88.23524736846694, "y": 40.09280968739862, "z": 202.48926726168128, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9113268162215618, "steering_wheel_angle": 11.006, "front_wheel_angle": 0.6124192772073712, "heading_rate": 1.0894641990981342, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059694.6295984}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.006, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059694.6295984}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059694.7297266, "x": -88.23524736846694, "y": 40.09280968739862, "z": 202.48926726168128, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9165188162215614, "steering_wheel_angle": 11.006, "front_wheel_angle": 0.6124192772073712, "heading_rate": 1.1004411683585686, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059694.729564}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.006, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059694.729564}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059694.8297129, "x": -88.23524736846694, "y": 40.09280968739862, "z": 202.48926726168128, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9537588162215616, "steering_wheel_angle": 11.006, "front_wheel_angle": 0.6124192772073712, "heading_rate": 1.177279953181611, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059694.8295588}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.29, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.006, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059694.8295588}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059694.9299777, "x": -88.23524736846694, "y": 40.09280968739862, "z": 202.48926726168128, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8921418162215615, "steering_wheel_angle": 11.006, "front_wheel_angle": 0.6124192772073712, "heading_rate": 1.0483005643715042, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059694.929629}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.006, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059694.929629}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059695.0298338, "x": -88.23524736846694, "y": 40.09280968739862, "z": 202.48926726168128, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9048818162215615, "steering_wheel_angle": 11.006, "front_wheel_angle": 0.6124192772073712, "heading_rate": 1.0757429875225908, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059695.0296092}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.006, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059695.0296092}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059695.12978, "x": -88.23525069435004, "y": 40.09279549356347, "z": 202.49613009843105, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9035988162215616, "steering_wheel_angle": 11.006, "front_wheel_angle": 0.6124192772073712, "heading_rate": 1.072998745207482, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059695.1295671}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.006, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059695.1295671}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059695.2303371, "x": -88.23525069435004, "y": 40.09279549356347, "z": 202.49613009843105, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9061668162215617, "steering_wheel_angle": 11.003, "front_wheel_angle": 0.6122075475416819, "heading_rate": 1.0780018436776206, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059695.2296824}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.003, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059695.2296824}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059695.3299215, "x": -88.23525069435004, "y": 40.09279549356347, "z": 202.49613009843105, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9204338162215615, "steering_wheel_angle": 11.003, "front_wheel_angle": 0.6122075475416819, "heading_rate": 1.1081749232716505, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059695.3296278}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.04, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.003, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059695.3296278}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059695.4297628, "x": -88.23525069435004, "y": 40.09279549356347, "z": 202.49613009843105, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9230538162215614, "steering_wheel_angle": 11.003, "front_wheel_angle": 0.6122075475416819, "heading_rate": 1.1136609377432924, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059695.4296007}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.003, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059695.4296007}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059695.5297732, "x": -88.23525069435004, "y": 40.09279549356347, "z": 202.49613009843105, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9113268162215618, "steering_wheel_angle": 11.003, "front_wheel_angle": 0.6122075475416819, "heading_rate": 1.0889738726209044, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059695.5295994}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.003, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059695.5295994}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059695.6297126, "x": -88.2352468295753, "y": 40.09278150768359, "z": 202.51975300898312, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9152178162215616, "steering_wheel_angle": 11.003, "front_wheel_angle": 0.6122075475416819, "heading_rate": 1.097202894328367, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059695.6295502}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.003, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059695.6295502}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059695.7298882, "x": -88.2352468295753, "y": 40.09278150768359, "z": 202.51975300898312, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9139188162215617, "steering_wheel_angle": 11.003, "front_wheel_angle": 0.6122075475416819, "heading_rate": 1.0944598870925462, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059695.7295861}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.003, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059695.7295861}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059695.8297935, "x": -88.2352468295753, "y": 40.09278150768359, "z": 202.51975300898312, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8908788162215617, "steering_wheel_angle": 11.003, "front_wheel_angle": 0.6122075475416819, "heading_rate": 1.0450857568477696, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059695.8295503}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.003, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059695.8295503}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059695.9298904, "x": -88.2352468295753, "y": 40.09278150768359, "z": 202.51975300898312, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8946738162215615, "steering_wheel_angle": 10.997, "front_wheel_angle": 0.6117842060592159, "heading_rate": 1.0523669243606113, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059695.929572}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.84, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.997, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059695.929572}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059696.0303495, "x": -88.2352468295753, "y": 40.09278150768359, "z": 202.51975300898312, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8972138162215613, "steering_wheel_angle": 10.997, "front_wheel_angle": 0.6117842060592159, "heading_rate": 1.0578480020916563, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059696.0297456}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.86, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.997, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059696.0297456}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059696.1299481, "x": -88.23523700027447, "y": 40.09276991752491, "z": 202.43639294605873, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8845938162215616, "steering_wheel_angle": 10.997, "front_wheel_angle": 0.6117842060592159, "heading_rate": 1.030442613436432, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059696.12962}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.76, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.997, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059696.12962}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059696.229897, "x": -88.23523700027447, "y": 40.09276991752491, "z": 202.43639294605873, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8758788162215616, "steering_wheel_angle": 10.997, "front_wheel_angle": 0.6117842060592159, "heading_rate": 1.011258841377775, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059696.2295847}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.997, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059696.2295847}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059696.3297067, "x": -88.23523700027447, "y": 40.09276991752491, "z": 202.43639294605873, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8672618162215615, "steering_wheel_angle": 10.997, "front_wheel_angle": 0.6117842060592159, "heading_rate": 0.992075069319118, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059696.3295815}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.997, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059696.3295815}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059696.4298627, "x": -88.23523700027447, "y": 40.09276991752491, "z": 202.43639294605873, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.864817816221562, "steering_wheel_angle": 10.997, "front_wheel_angle": 0.6117842060592159, "heading_rate": 0.9865939915880733, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059696.4296188}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.6, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.997, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059696.4296188}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059696.5298252, "x": -88.23523700027447, "y": 40.09276991752491, "z": 202.43639294605873, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.887101816221562, "steering_wheel_angle": 10.997, "front_wheel_angle": 0.6117842060592159, "heading_rate": 1.0359236911674767, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059696.5296168}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.78, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.997, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059696.5296168}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059696.6297543, "x": -88.23522264104203, "y": 40.092762711680194, "z": 202.3523252053586, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8783588162215614, "steering_wheel_angle": 10.997, "front_wheel_angle": 0.6117842060592159, "heading_rate": 1.01673991910882, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059696.629555}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.71, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.997, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059696.629555}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059696.730182, "x": -88.23522264104203, "y": 40.092762711680194, "z": 202.3523252053586, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8672618162215615, "steering_wheel_angle": 10.997, "front_wheel_angle": 0.6117842060592159, "heading_rate": 0.992075069319118, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059696.7296414}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.997, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059696.7296414}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059696.829713, "x": -88.23522264104203, "y": 40.092762711680194, "z": 202.3523252053586, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.858742816221562, "steering_wheel_angle": 10.995, "front_wheel_angle": 0.6116431271261784, "heading_rate": 0.9725993946417988, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059696.8295624}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.55, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.995, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059696.8295624}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059696.9299483, "x": -88.23522264104203, "y": 40.092762711680194, "z": 202.3523252053586, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8551218162215615, "steering_wheel_angle": 10.995, "front_wheel_angle": 0.6116431271261784, "heading_rate": 0.9643802448279245, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059696.929605}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.995, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059696.929605}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059697.0299044, "x": -88.23522264104203, "y": 40.092762711680194, "z": 202.3523252053586, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8443668162215614, "steering_wheel_angle": 10.994, "front_wheel_angle": 0.6115725941987299, "heading_rate": 0.9395818116420757, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059697.029619}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.994, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059697.029619}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059697.1297882, "x": -88.23520655323992, "y": 40.09276030689957, "z": 202.30953679780802, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8443668162215614, "steering_wheel_angle": 10.994, "front_wheel_angle": 0.6115725941987299, "heading_rate": 0.9395818116420757, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059697.1296022}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.994, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059697.1296022}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059697.2298334, "x": -88.23520655323992, "y": 40.09276030689957, "z": 202.30953679780802, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8337738162215613, "steering_wheel_angle": 10.994, "front_wheel_angle": 0.6115725941987299, "heading_rate": 0.914928061482371, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059697.2295742}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.994, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059697.2295742}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059697.3297215, "x": -88.23520655323992, "y": 40.09276030689957, "z": 202.30953679780802, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8302788162215617, "steering_wheel_angle": 10.994, "front_wheel_angle": 0.6115725941987299, "heading_rate": 0.9067101447624695, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059697.3295553}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.994, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059697.3295553}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059697.4300108, "x": -88.23520655323992, "y": 40.09276030689957, "z": 202.30953679780802, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8291178162215616, "steering_wheel_angle": 10.991, "front_wheel_angle": 0.6113610215629693, "heading_rate": 0.9035640489339581, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059697.4296417}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.991, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059697.4296417}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059697.5297465, "x": -88.23520655323992, "y": 40.09276030689957, "z": 202.30953679780802, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8256468162215613, "steering_wheel_angle": 10.986, "front_wheel_angle": 0.6110084876102121, "heading_rate": 0.8946784414894243, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059697.5295916}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.27, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.986, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059697.5295916}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059697.6299598, "x": -88.23519159645552, "y": 40.092762290377756, "z": 202.30323099512702, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8199018162215617, "steering_wheel_angle": 10.984, "front_wheel_angle": 0.610867504497683, "heading_rate": 0.8807340423537865, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059697.6295846}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.984, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059697.6295846}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059697.7297306, "x": -88.23519159645552, "y": 40.092762290377756, "z": 202.30323099512702, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8233428162215617, "steering_wheel_angle": 10.976, "front_wheel_angle": 0.6103037459926036, "heading_rate": 0.8878734419530052, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059697.7295966}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.25, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.976, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059697.7295966}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059697.8297775, "x": -88.23519159645552, "y": 40.092762290377756, "z": 202.30323099512702, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8119428162215616, "steering_wheel_angle": 10.943, "front_wheel_angle": 0.6079811762227766, "heading_rate": 0.8563054723333868, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059697.8295984}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.943, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059697.8295984}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059697.9298253, "x": -88.23519159645552, "y": 40.092762290377756, "z": 202.30323099512702, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8176178162215617, "steering_wheel_angle": 10.927, "front_wheel_angle": 0.6068567759908587, "heading_rate": 0.8678130660647361, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059697.9295964}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.927, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059697.9295964}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059698.0299811, "x": -88.23519159645552, "y": 40.092762290377756, "z": 202.30323099512702, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8063178162215614, "steering_wheel_angle": 10.927, "front_wheel_angle": 0.6068567759908587, "heading_rate": 0.8406939077502131, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059698.0296102}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.927, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059698.0296102}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059698.1297336, "x": -88.23517891565996, "y": 40.09276823079517, "z": 202.36390755959764, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8164788162215615, "steering_wheel_angle": 10.927, "front_wheel_angle": 0.6068567759908587, "heading_rate": 0.8651011502332838, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059698.129598}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.19, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.927, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059698.129598}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059698.2297633, "x": -88.23517891565996, "y": 40.09276823079517, "z": 202.36390755959764, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8085618162215615, "steering_wheel_angle": 10.927, "front_wheel_angle": 0.6068567759908587, "heading_rate": 0.8461177394131177, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059698.2296062}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.927, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059698.2296062}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059698.3299935, "x": -88.23517891565996, "y": 40.09276823079517, "z": 202.36390755959764, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8176178162215617, "steering_wheel_angle": 10.927, "front_wheel_angle": 0.6068567759908587, "heading_rate": 0.8678130660647361, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059698.3296325}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.927, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059698.3296325}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059698.4300032, "x": -88.23517891565996, "y": 40.09276823079517, "z": 202.36390755959764, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8199018162215617, "steering_wheel_angle": 10.928, "front_wheel_angle": 0.6069270186862324, "heading_rate": 0.8733678405443939, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059698.4296265}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.928, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059698.4296265}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059698.5298655, "x": -88.23517891565996, "y": 40.09276823079517, "z": 202.36390755959764, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8176178162215617, "steering_wheel_angle": 10.928, "front_wheel_angle": 0.6069270186862324, "heading_rate": 0.8679431955720682, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059698.5295987}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.928, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059698.5295987}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059698.6298053, "x": -88.23516912905724, "y": 40.09277694320582, "z": 202.40839344333241, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8210468162215614, "steering_wheel_angle": 10.931, "front_wheel_angle": 0.6071377726086243, "heading_rate": 0.8764743366663263, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059698.6296227}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.931, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059698.6296227}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059698.7297351, "x": -88.23516912905724, "y": 40.09277694320582, "z": 202.40839344333241, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8256468162215613, "steering_wheel_angle": 10.941, "front_wheel_angle": 0.6078405658166314, "heading_rate": 0.888660067015333, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059698.729561}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.27, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.941, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059698.729561}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059698.829696, "x": -88.23516912905724, "y": 40.09277694320582, "z": 202.40839344333241, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8326068162215616, "steering_wheel_angle": 10.949, "front_wheel_angle": 0.6084031110847591, "heading_rate": 0.906052104603376, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059698.8295524}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.949, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059698.8295524}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059698.9298234, "x": -88.23516912905724, "y": 40.09277694320582, "z": 202.40839344333241, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8291178162215616, "steering_wheel_angle": 10.95, "front_wheel_angle": 0.6084734486847982, "heading_rate": 0.8980241397347448, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059698.9296167}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.95, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059698.9296167}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059699.0299785, "x": -88.23516912905724, "y": 40.09277694320582, "z": 202.40839344333241, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.824493816221562, "steering_wheel_angle": 10.95, "front_wheel_angle": 0.6084734486847982, "heading_rate": 0.8871389986470509, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059699.0295906}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.26, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.95, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059699.0295906}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059699.1299765, "x": -88.23516303717054, "y": 40.092787649339854, "z": 202.40183589685407, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8384618162215616, "steering_wheel_angle": 10.95, "front_wheel_angle": 0.6084734486847982, "heading_rate": 0.9197944219101327, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059699.1296737}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.95, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059699.1296737}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059699.2298539, "x": -88.23516303717054, "y": 40.092787649339854, "z": 202.40183589685407, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8268018162215616, "steering_wheel_angle": 10.95, "front_wheel_angle": 0.6084734486847982, "heading_rate": 0.8925815691908978, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059699.2296147}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.95, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059699.2296147}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059699.3300357, "x": -88.23516303717054, "y": 40.092787649339854, "z": 202.40183589685407, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8467428162215613, "steering_wheel_angle": 10.95, "front_wheel_angle": 0.6084734486847982, "heading_rate": 0.9388434188135969, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059699.3296368}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.45, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.95, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059699.3296368}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059699.4297016, "x": -88.23516303717054, "y": 40.092787649339854, "z": 202.40183589685407, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8443668162215614, "steering_wheel_angle": 10.95, "front_wheel_angle": 0.6084734486847982, "heading_rate": 0.9334008482697499, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059699.4295588}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.95, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059699.4295588}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059699.5301473, "x": -88.23516303717054, "y": 40.092787649339854, "z": 202.40183589685407, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8443668162215614, "steering_wheel_angle": 10.95, "front_wheel_angle": 0.6084734486847982, "heading_rate": 0.9334008482697499, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059699.5296266}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.95, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059699.5296266}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059699.6296828, "x": -88.23516196379268, "y": 40.092799563151395, "z": 202.43334399402133, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8443668162215614, "steering_wheel_angle": 10.95, "front_wheel_angle": 0.6084734486847982, "heading_rate": 0.9334008482697499, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059699.6295784}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.95, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059699.6295784}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059699.7296922, "x": -88.23516196379268, "y": 40.092799563151395, "z": 202.43334399402133, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8455538162215617, "steering_wheel_angle": 10.948, "front_wheel_angle": 0.6083327778069164, "heading_rate": 0.9358413962467406, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059699.7295654}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.948, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059699.7295654}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059699.8299937, "x": -88.23516196379268, "y": 40.092799563151395, "z": 202.43334399402133, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8551218162215615, "steering_wheel_angle": 10.948, "front_wheel_angle": 0.6083327778069164, "heading_rate": 0.9576051496478275, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059699.8296318}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.948, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059699.8296318}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059699.9297435, "x": -88.23516196379268, "y": 40.092799563151395, "z": 202.43334399402133, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8503218162215616, "steering_wheel_angle": 10.947, "front_wheel_angle": 0.6082624488504736, "heading_rate": 0.9465813060584185, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059699.9295557}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.947, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059699.9295557}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059700.030242, "x": -88.23516196379268, "y": 40.092799563151395, "z": 202.43334399402133, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.858742816221562, "steering_wheel_angle": 10.936, "front_wheel_angle": 0.6074891153143884, "heading_rate": 0.9640302081912957, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059700.0296757}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.55, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.936, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059700.0296757}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059700.1304502, "x": -88.23516631555549, "y": 40.0928112739535, "z": 202.49302298911272, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8771178162215616, "steering_wheel_angle": 10.812, "front_wheel_angle": 0.5988073796924983, "heading_rate": 0.9862630632975705, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059700.1297026}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.7, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.812, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059700.1297026}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059700.2299635, "x": -88.23516631555549, "y": 40.0928112739535, "z": 202.49302298911272, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8551218162215615, "steering_wheel_angle": 10.481, "front_wheel_angle": 0.5759463159424426, "heading_rate": 0.8929113230752561, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059700.2296221}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.481, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059700.2296221}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059700.3298535, "x": -88.23516631555549, "y": 40.0928112739535, "z": 202.49302298911272, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8734068162215616, "steering_wheel_angle": 10.119, "front_wheel_angle": 0.5514420630314834, "heading_rate": 0.8817907596595136, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059700.3295772}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.119, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059700.3295772}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059700.4301975, "x": -88.23516631555549, "y": 40.0928112739535, "z": 202.49302298911272, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8721738162215615, "steering_wheel_angle": 9.796, "front_wheel_angle": 0.5299921848598459, "heading_rate": 0.8376632200615568, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059700.4296505}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.796, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059700.4296505}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059700.530224, "x": -88.23516631555549, "y": 40.0928112739535, "z": 202.49302298911272, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8734068162215616, "steering_wheel_angle": 9.506, "front_wheel_angle": 0.5110493691050984, "heading_rate": 0.803869378700158, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059700.5297246}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.506, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059700.5297246}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059700.629779, "x": -88.23517555546023, "y": 40.09282219790652, "z": 202.53508414638097, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.887101816221562, "steering_wheel_angle": 9.336, "front_wheel_angle": 0.5000781066535017, "heading_rate": 0.8067995255380606, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059700.6295757}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.78, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.336, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059700.6295757}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059700.7301428, "x": -88.23517555546023, "y": 40.09282219790652, "z": 202.53508414638097, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8908788162215617, "steering_wheel_angle": 9.158, "front_wheel_angle": 0.4886925781756963, "heading_rate": 0.7913339175672062, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059700.7297664}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.158, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059700.7297664}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059700.8298786, "x": -88.23517555546023, "y": 40.09282219790652, "z": 202.53508414638097, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8972138162215613, "steering_wheel_angle": 8.761, "front_wheel_angle": 0.46366115008775205, "heading_rate": 0.7539317719479999, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059700.8295934}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.86, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.761, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059700.8295934}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059700.9298382, "x": -88.23517555546023, "y": 40.09282219790652, "z": 202.53508414638097, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9074538162215617, "steering_wheel_angle": 8.125, "front_wheel_angle": 0.42454311523330945, "heading_rate": 0.6957067266743504, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059700.9295757}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.94, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.125, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059700.9295757}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059701.0297642, "x": -88.23517555546023, "y": 40.09282219790652, "z": 202.53508414638097, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.934942816221562, "steering_wheel_angle": 7.686, "front_wheel_angle": 0.3982005633881346, "heading_rate": 0.6819515636300723, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059701.029604}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.686, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059701.029604}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059701.1299155, "x": -88.23518981214865, "y": 40.09283206599428, "z": 202.5250536936116, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9376068162215616, "steering_wheel_angle": 7.417, "front_wheel_angle": 0.3823091323224739, "heading_rate": 0.6549713241085799, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059701.129579}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.17, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.417, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059701.129579}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059701.2296996, "x": -88.23518981214865, "y": 40.09283206599428, "z": 202.5250536936116, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9743538162215617, "steering_wheel_angle": 6.93, "front_wheel_angle": 0.3539982992562818, "heading_rate": 0.6409663739704577, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059701.2295816}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.93, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059701.2295816}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059701.3298995, "x": -88.23518981214865, "y": 40.09283206599428, "z": 202.5250536936116, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.964686816221562, "steering_wheel_angle": 6.333, "front_wheel_angle": 0.32005574924422325, "heading_rate": 0.5657976892864415, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059701.3295648}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.37, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.333, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059701.3295648}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059701.430137, "x": -88.23518981214865, "y": 40.09283206599428, "z": 202.5250536936116, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.037361816221561, "steering_wheel_angle": 5.579, "front_wheel_angle": 0.2783029658361208, "heading_rate": 0.5446496753793076, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059701.4295907}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.88, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.579, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059701.4295907}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059701.5298474, "x": -88.23518981214865, "y": 40.09283206599428, "z": 202.5250536936116, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.027078816221562, "steering_wheel_angle": 4.764, "front_wheel_angle": 0.23446285622069388, "heading_rate": 0.44878773406565486, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059701.529578}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059701.529578}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059701.6299014, "x": -88.23521062709092, "y": 40.092840840495604, "z": 202.5296698673835, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": 4.362, "front_wheel_angle": 0.21329829692599925, "heading_rate": 0.42895570806466865, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059701.6296368}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059701.6296368}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059701.7299936, "x": -88.23521062709092, "y": 40.092840840495604, "z": 202.5296698673835, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": 4.071, "front_wheel_angle": 0.1981574283653751, "heading_rate": 0.41021272951466037, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059701.7295692}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.071, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059701.7295692}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059701.8297167, "x": -88.23521062709092, "y": 40.092840840495604, "z": 202.5296698673835, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": 3.938, "front_wheel_angle": 0.19128625166418547, "heading_rate": 0.4016807463531835, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059701.8295786}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.938, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059701.8295786}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059701.9297214, "x": -88.23521062709092, "y": 40.092840840495604, "z": 202.5296698673835, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.142353816221561, "steering_wheel_angle": 4.088, "front_wheel_angle": 0.19903788902453867, "heading_rate": 0.4380858332415404, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059701.9295807}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.088, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059701.9295807}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059702.0296614, "x": -88.23521062709092, "y": 40.092840840495604, "z": 202.5296698673835, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.183278816221561, "steering_wheel_angle": 4.421, "front_wheel_angle": 0.21638628552779446, "heading_rate": 0.49890662504732164, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059702.029543}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.421, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059702.029543}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059702.1301692, "x": -88.23521062709092, "y": 40.092840840495604, "z": 202.5296698673835, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.210126816221561, "steering_wheel_angle": 4.515, "front_wheel_angle": 0.22131899272245154, "heading_rate": 0.5247181800903767, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059702.1296635}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.515, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059702.1296635}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059702.2297628, "x": -88.235238297859, "y": 40.09284813489146, "z": 202.5748418936134, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.210126816221561, "steering_wheel_angle": 4.254, "front_wheel_angle": 0.20766169356151365, "heading_rate": 0.49135693839110134, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059702.2295973}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.254, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059702.2295973}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059702.3298542, "x": -88.235238297859, "y": 40.09284813489146, "z": 202.5748418936134, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.210126816221561, "steering_wheel_angle": 4.015, "front_wheel_angle": 0.19526060713848714, "heading_rate": 0.46123052462423875, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059702.3296149}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059702.3296149}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059702.4298847, "x": -88.235238297859, "y": 40.09284813489146, "z": 202.5748418936134, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": 3.99, "front_wheel_angle": 0.19396912123243001, "heading_rate": 0.4895626465048309, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059702.4296079}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.99, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059702.4296079}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059702.5300102, "x": -88.235238297859, "y": 40.09284813489146, "z": 202.5748418936134, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.2531018162215615, "steering_wheel_angle": 4.06, "front_wheel_angle": 0.1975879841121795, "heading_rate": 0.486423750777087, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059702.5295837}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.06, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059702.5295837}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059702.629736, "x": -88.23527109528213, "y": 40.092851835471365, "z": 202.60095486422406, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": 4.112, "front_wheel_angle": 0.20028174227256046, "heading_rate": 0.5122663208113967, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059702.6295867}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.112, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059702.6295867}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059702.7297099, "x": -88.23527109528213, "y": 40.092851835471365, "z": 202.60095486422406, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3099338162215615, "steering_wheel_angle": 4.119, "front_wheel_angle": 0.20064472054495194, "heading_rate": 0.5195757576373353, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059702.7295766}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.54, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.119, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059702.7295766}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059702.8297827, "x": -88.23527109528213, "y": 40.092851835471365, "z": 202.60095486422406, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": 4.08, "front_wheel_angle": 0.1986234924705042, "heading_rate": 0.5016209312689108, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059702.8295598}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.08, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059702.8295598}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059702.9297135, "x": -88.23527109528213, "y": 40.092851835471365, "z": 202.60095486422406, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": 3.977, "front_wheel_angle": 0.1932979711918885, "heading_rate": 0.493942636235738, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059702.9295812}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.977, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059702.9295812}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059703.0299783, "x": -88.23527109528213, "y": 40.092851835471365, "z": 202.60095486422406, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": 3.842, "front_wheel_angle": 0.18634533223400704, "heading_rate": 0.47575033353090057, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059703.029614}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.842, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059703.029614}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059703.1300035, "x": -88.23530649880583, "y": 40.09284924448476, "z": 202.60976465768334, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": 3.67, "front_wheel_angle": 0.17753160389751646, "heading_rate": 0.45275651113935966, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059703.1296308}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.67, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059703.1296308}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059703.2299407, "x": -88.23530649880583, "y": 40.09284924448476, "z": 202.60976465768334, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3099338162215615, "steering_wheel_angle": 3.642, "front_wheel_angle": 0.17610147345028354, "heading_rate": 0.45459321772752787, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059703.2296264}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.54, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.642, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059703.2296264}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059703.32994, "x": -88.23530649880583, "y": 40.09284924448476, "z": 202.60976465768334, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3099338162215615, "steering_wheel_angle": 3.693, "front_wheel_angle": 0.17870732581305654, "heading_rate": 0.4614643517135304, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059703.3295743}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.54, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.693, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059703.3295743}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059703.4297402, "x": -88.23530649880583, "y": 40.09284924448476, "z": 202.60976465768334, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": 3.727, "front_wheel_angle": 0.1804469597079768, "heading_rate": 0.46035405040094907, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059703.4295552}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.727, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059703.4295552}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059703.529655, "x": -88.23530649880583, "y": 40.09284924448476, "z": 202.60976465768334, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": 3.717, "front_wheel_angle": 0.1799351029705097, "heading_rate": 0.4590195491480339, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059703.5295422}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.717, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059703.5295422}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059703.6298838, "x": -88.23534049884971, "y": 40.09284026936029, "z": 202.65544187188135, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": 3.678, "front_wheel_angle": 0.17794045110696424, "heading_rate": 0.44820142140178504, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059703.629567}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.678, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059703.629567}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059703.7299838, "x": -88.23534049884971, "y": 40.09284026936029, "z": 202.65544187188135, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": 3.571, "front_wheel_angle": 0.17248087226687514, "heading_rate": 0.4341686929118294, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059703.7296228}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.571, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059703.7296228}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059703.8298552, "x": -88.23534049884971, "y": 40.09284026936029, "z": 202.65544187188135, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.267117816221561, "steering_wheel_angle": 3.359, "front_wheel_angle": 0.1617190849471584, "heading_rate": 0.4014867139947157, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059703.8295722}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.359, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059703.8295722}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059703.9300709, "x": -88.23534049884971, "y": 40.09284026936029, "z": 202.65544187188135, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.2531018162215615, "steering_wheel_angle": 3.043, "front_wheel_angle": 0.14581168508156775, "heading_rate": 0.3568091320429755, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059703.929629}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.043, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059703.929629}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059704.030007, "x": -88.23534049884971, "y": 40.09284026936029, "z": 202.65544187188135, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3099338162215615, "steering_wheel_angle": 2.619, "front_wheel_angle": 0.12471171618537553, "heading_rate": 0.3202615303776453, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059704.0296578}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.54, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.619, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059704.0296578}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059704.1297233, "x": -88.23537086496805, "y": 40.09282607083627, "z": 202.61194049656152, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": 2.104, "front_wheel_angle": 0.09944530464659641, "heading_rate": 0.2517745223343258, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059704.129581}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.104, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059704.129581}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059704.2298226, "x": -88.23537086496805, "y": 40.09282607083627, "z": 202.61194049656152, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.267117816221561, "steering_wheel_angle": 1.435, "front_wheel_angle": 0.06718888562398856, "heading_rate": 0.16559691051164135, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059704.2296016}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.435, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059704.2296016}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059704.3297884, "x": -88.23537086496805, "y": 40.09282607083627, "z": 202.61194049656152, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.2531018162215615, "steering_wheel_angle": 0.705, "front_wheel_angle": 0.03268122101064127, "heading_rate": 0.0794334361385109, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059704.3295798}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.705, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059704.3295798}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059704.4302704, "x": -88.23537086496805, "y": 40.09282607083627, "z": 202.61194049656152, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.237486816221562, "steering_wheel_angle": 0.026, "front_wheel_angle": 0.001194436781101673, "heading_rate": 0.002860117558654261, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059704.429708}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059704.429708}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059704.5300758, "x": -88.23537086496805, "y": 40.09282607083627, "z": 202.61194049656152, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.237486816221562, "steering_wheel_angle": -0.634, "front_wheel_angle": -0.029361859998389816, "heading_rate": -0.0703281028796981, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059704.5295951}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.634, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059704.5295951}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059704.629825, "x": -88.2353996793728, "y": 40.09280904825704, "z": 202.51790861961854, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.267117816221561, "steering_wheel_angle": -1.177, "front_wheel_angle": -0.05491290011400435, "heading_rate": -0.1352732112788958, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059704.6295946}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.177, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059704.6295946}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059704.7298262, "x": -88.2353996793728, "y": 40.09280904825704, "z": 202.51790861961854, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.2531018162215615, "steering_wheel_angle": -1.709, "front_wheel_angle": -0.08032482027761152, "heading_rate": -0.1955850360357253, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059704.7295792}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.709, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059704.7295792}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059704.830155, "x": -88.2353996793728, "y": 40.09280904825704, "z": 202.51790861961854, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.237486816221562, "steering_wheel_angle": -2.345, "front_wheel_angle": -0.11122059705355693, "heading_rate": -0.2674247891467091, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059704.829678}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.345, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059704.829678}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059704.9297256, "x": -88.2353996793728, "y": 40.09280904825704, "z": 202.51790861961854, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.2531018162215615, "steering_wheel_angle": -2.783, "front_wheel_angle": -0.1328404358501562, "heading_rate": -0.3246727852553291, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059704.9295785}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.783, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059704.9295785}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059705.0296576, "x": -88.2353996793728, "y": 40.09280904825704, "z": 202.51790861961854, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.2531018162215615, "steering_wheel_angle": -3.045, "front_wheel_angle": -0.14591186969619796, "heading_rate": -0.35705780256376957, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059705.029539}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.045, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059705.029539}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059705.1297603, "x": -88.2354303508381, "y": 40.092793722854154, "z": 202.46029223310845, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.223742816221561, "steering_wheel_angle": -3.212, "front_wheel_angle": -0.15429943387509293, "heading_rate": -0.3675747111258736, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059705.129548}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.212, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059705.129548}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059705.229647, "x": -88.2354303508381, "y": 40.092793722854154, "z": 202.46029223310845, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.223742816221561, "steering_wheel_angle": -3.332, "front_wheel_angle": -0.16035370049248587, "heading_rate": -0.38224276588347633, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059705.229552}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.332, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059705.229552}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059705.3297222, "x": -88.2354303508381, "y": 40.092793722854154, "z": 202.46029223310845, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.2531018162215615, "steering_wheel_angle": -3.47, "front_wheel_angle": -0.16734468451794138, "heading_rate": -0.4104337557343993, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059705.3295472}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.47, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059705.3295472}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059705.4298332, "x": -88.2354303508381, "y": 40.092793722854154, "z": 202.46029223310845, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.237486816221562, "steering_wheel_angle": -3.669, "front_wheel_angle": -0.17748050545630628, "heading_rate": -0.42950178801779754, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059705.4295812}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.669, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059705.4295812}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059705.5298142, "x": -88.2354303508381, "y": 40.092793722854154, "z": 202.46029223310845, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.210126816221561, "steering_wheel_angle": -3.937, "front_wheel_angle": -0.19123470318643707, "heading_rate": -0.45148244718823993, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059705.5295904}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.937, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059705.5295904}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059705.6298788, "x": -88.23546406152374, "y": 40.09278338188964, "z": 202.48997900243745, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.223742816221561, "steering_wheel_angle": -4.224, "front_wheel_angle": -0.2060996154366972, "heading_rate": -0.4940870347760186, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059705.6296537}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.224, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059705.6296537}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059705.729912, "x": -88.23546406152374, "y": 40.09278338188964, "z": 202.48997900243745, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.223742816221561, "steering_wheel_angle": -4.365, "front_wheel_angle": -0.21345516383014815, "heading_rate": -0.5122583488752932, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059705.7295635}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.365, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059705.7295635}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059705.829743, "x": -88.23546406152374, "y": 40.09278338188964, "z": 202.48997900243745, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.210126816221561, "steering_wheel_angle": -4.422, "front_wheel_angle": -0.2164386778018133, "heading_rate": -0.512773964248198, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059705.8295486}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.422, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059705.8295486}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059705.929687, "x": -88.23546406152374, "y": 40.09278338188964, "z": 202.48997900243745, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.210126816221561, "steering_wheel_angle": -4.44, "front_wheel_angle": -0.21738204440488262, "heading_rate": -0.5150807686653613, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059705.9295459}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.44, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059705.9295459}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059706.029678, "x": -88.23546406152374, "y": 40.09278338188964, "z": 202.48997900243745, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1966388162215615, "steering_wheel_angle": -4.432, "front_wheel_angle": -0.2169626988303158, "heading_rate": -0.507166716639959, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059706.0295858}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.432, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059706.0295858}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059706.1298637, "x": -88.2354996643071, "y": 40.092779804447204, "z": 202.5368433341082, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1966388162215615, "steering_wheel_angle": -4.416, "front_wheel_angle": -0.21612435094898022, "heading_rate": -0.5051445108644231, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059706.129553}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059706.129553}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059706.2299218, "x": -88.2354996643071, "y": 40.092779804447204, "z": 202.5368433341082, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1966388162215615, "steering_wheel_angle": -4.418, "front_wheel_angle": -0.2162291194229802, "heading_rate": -0.5053971854945928, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059706.2295852}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.418, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059706.2295852}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059706.3307977, "x": -88.2354996643071, "y": 40.092779804447204, "z": 202.5368433341082, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.183278816221561, "steering_wheel_angle": -4.431, "front_wheel_angle": -0.21691028868295123, "heading_rate": -0.5001534796720106, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059706.3296907}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.431, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059706.3296907}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059706.4300263, "x": -88.2354996643071, "y": 40.092779804447204, "z": 202.5368433341082, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.183278816221561, "steering_wheel_angle": -4.431, "front_wheel_angle": -0.21691028868295123, "heading_rate": -0.5001534796720106, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059706.4296381}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.431, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059706.4296381}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059706.5298314, "x": -88.2354996643071, "y": 40.092779804447204, "z": 202.5368433341082, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.183278816221561, "steering_wheel_angle": -4.443, "front_wheel_angle": -0.21753932852210958, "heading_rate": -0.5016506473586053, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059706.529595}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.443, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059706.529595}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059706.629786, "x": -88.23553484622987, "y": 40.09278274293391, "z": 202.6036237102973, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1966388162215615, "steering_wheel_angle": -4.444, "front_wheel_angle": -0.21759176014165382, "heading_rate": -0.5086845863079114, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059706.6295626}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059706.6295626}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059706.7296457, "x": -88.23553484622987, "y": 40.09278274293391, "z": 202.6036237102973, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.210126816221561, "steering_wheel_angle": -4.444, "front_wheel_angle": -0.21759176014165382, "heading_rate": -0.5155937148146402, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059706.7294786}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059706.7294786}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059706.8297896, "x": -88.23553484622987, "y": 40.09278274293391, "z": 202.6036237102973, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": -4.44, "front_wheel_angle": -0.21738204440488262, "heading_rate": -0.47280445766937695, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059706.8295827}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.44, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059706.8295827}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059706.929664, "x": -88.23553484622987, "y": 40.09278274293391, "z": 202.6036237102973, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": -4.439, "front_wheel_angle": -0.21732961994566383, "heading_rate": -0.4933883733427153, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059706.9295633}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.439, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059706.9295633}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059707.0297315, "x": -88.23553484622987, "y": 40.09278274293391, "z": 202.6036237102973, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": -4.442, "front_wheel_angle": -0.21748689869292215, "heading_rate": -0.49375694115042806, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059707.0295045}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.442, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059707.0295045}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059707.1297193, "x": -88.23556749810844, "y": 40.09279151958652, "z": 202.58630204603216, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": -4.422, "front_wheel_angle": -0.2164386778018133, "heading_rate": -0.4706869889581449, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059707.1295993}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.422, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059707.1295993}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059707.2300804, "x": -88.23556749810844, "y": 40.09279151958652, "z": 202.58630204603216, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": -4.207, "front_wheel_angle": -0.2052151376351446, "heading_rate": -0.4455609587916295, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059707.2296226}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.207, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059707.2296226}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059707.3297946, "x": -88.23556749810844, "y": 40.09279151958652, "z": 202.58630204603216, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.142353816221561, "steering_wheel_angle": -3.794, "front_wheel_angle": -0.18388070692117287, "heading_rate": -0.40392876751475915, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059707.3296106}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.794, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059707.3296106}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059707.4297347, "x": -88.23556749810844, "y": 40.09279151958652, "z": 202.58630204603216, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.183278816221561, "steering_wheel_angle": -3.32, "front_wheel_angle": -0.15974723855201903, "heading_rate": -0.36566716348049894, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059707.429582}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.32, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059707.429582}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059707.529749, "x": -88.23556749810844, "y": 40.09279151958652, "z": 202.58630204603216, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": -2.814, "front_wheel_angle": -0.13438154971127786, "heading_rate": -0.28940466755756056, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059707.5295532}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.814, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059707.5295532}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059707.6301556, "x": -88.23559601624197, "y": 40.09280478301462, "z": 202.6021970204995, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.142353816221561, "steering_wheel_angle": -2.232, "front_wheel_angle": -0.10568892093580615, "heading_rate": -0.23040163814255485, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059707.6296122}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.232, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059707.6296122}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059707.729817, "x": -88.23559601624197, "y": 40.09280478301462, "z": 202.6021970204995, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": -1.525, "front_wheel_angle": -0.07149229094645726, "heading_rate": -0.15106150483946215, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059707.7296283}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.525, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059707.7296283}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059707.8298175, "x": -88.23559601624197, "y": 40.09280478301462, "z": 202.6021970204995, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": -0.808, "front_wheel_angle": -0.03750804938290355, "heading_rate": -0.08384637138942733, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059707.8295841}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.808, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059707.8295841}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059707.9298134, "x": -88.23559601624197, "y": 40.09280478301462, "z": 202.6021970204995, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": -0.109, "front_wheel_angle": -0.0050129081195356496, "heading_rate": -0.010397955111310917, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059707.9295907}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.109, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059707.9295907}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059708.0297656, "x": -88.23559601624197, "y": 40.09280478301462, "z": 202.6021970204995, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.183278816221561, "steering_wheel_angle": 0.565, "front_wheel_angle": 0.02614211558334401, "heading_rate": 0.0593438676084263, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059708.0295908}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.565, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059708.0295908}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059708.1297035, "x": -88.2356224418326, "y": 40.09281888852954, "z": 202.6105418910741, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": 1.248, "front_wheel_angle": 0.05828230664022176, "heading_rate": 0.12307863108801688, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059708.1295483}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.248, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059708.1295483}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059708.229682, "x": -88.2356224418326, "y": 40.09281888852954, "z": 202.6105418910741, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": 1.931, "front_wheel_angle": 0.09104394191879546, "heading_rate": 0.20399024443189437, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059708.229571}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.931, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059708.229571}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059708.3297153, "x": -88.2356224418326, "y": 40.09281888852954, "z": 202.6105418910741, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.142353816221561, "steering_wheel_angle": 2.599, "front_wheel_angle": 0.12372318341260312, "heading_rate": 0.2700908292084312, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059708.3295538}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.599, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059708.3295538}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059708.4296846, "x": -88.2356224418326, "y": 40.09281888852954, "z": 202.6105418910741, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": 3.232, "front_wheel_angle": 0.15530688509899468, "heading_rate": 0.34493828111962543, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059708.4295728}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.232, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059708.4295728}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059708.5297656, "x": -88.2356224418326, "y": 40.09281888852954, "z": 202.6105418910741, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.183278816221561, "steering_wheel_angle": 3.704, "front_wheel_angle": 0.17926993810559985, "heading_rate": 0.41127399676961035, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059708.5295346}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.704, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059708.5295346}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059708.629912, "x": -88.23565028498685, "y": 40.09283018973542, "z": 202.6498737896396, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": 4.2, "front_wheel_angle": 0.20485108776870037, "heading_rate": 0.4577333056230127, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059708.6295776}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.2, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059708.6295776}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059708.7301607, "x": -88.23565028498685, "y": 40.09283018973542, "z": 202.6498737896396, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": 4.577, "front_wheel_angle": 0.22458119337492408, "heading_rate": 0.5104087092149644, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059708.7296348}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.577, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059708.7296348}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059708.8300064, "x": -88.23565028498685, "y": 40.09283018973542, "z": 202.6498737896396, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": 4.683, "front_wheel_angle": 0.23017469157303241, "heading_rate": 0.5162530787902869, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059708.8296478}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.683, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059708.8296478}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059708.9296918, "x": -88.23565028498685, "y": 40.09283018973542, "z": 202.6498737896396, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": 4.778, "front_wheel_angle": 0.23520524845098917, "heading_rate": 0.5279584798246215, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059708.9295561}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.778, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059708.9295561}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059709.029731, "x": -88.23565028498685, "y": 40.09283018973542, "z": 202.6498737896396, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": 4.862, "front_wheel_angle": 0.23966724999623354, "heading_rate": 0.5383645570391341, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059709.0295782}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.862, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059709.0295782}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059709.1296709, "x": -88.23568024950353, "y": 40.092835930378875, "z": 202.6434026821212, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": 4.862, "front_wheel_angle": 0.23966724999623354, "heading_rate": 0.5460009337347247, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059709.129542}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.862, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059709.129542}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059709.229819, "x": -88.23568024950353, "y": 40.092835930378875, "z": 202.6434026821212, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.142353816221561, "steering_wheel_angle": 4.884, "front_wheel_angle": 0.24083804519036184, "heading_rate": 0.5334236150225219, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059709.2295961}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.884, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059709.2295961}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059709.3297024, "x": -88.23568024950353, "y": 40.092835930378875, "z": 202.6434026821212, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": 4.919, "front_wheel_angle": 0.2427025444750759, "heading_rate": 0.5454562860929392, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059709.3295434}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.919, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059709.3295434}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059709.429755, "x": -88.23568024950353, "y": 40.092835930378875, "z": 202.6434026821212, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": 5.015, "front_wheel_angle": 0.24782845515319105, "heading_rate": 0.5574568751690979, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059709.4295816}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059709.4295816}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059709.5296085, "x": -88.23568024950353, "y": 40.092835930378875, "z": 202.6434026821212, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.142353816221561, "steering_wheel_angle": 5.151, "front_wheel_angle": 0.25512018962910005, "heading_rate": 0.5664318030592149, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059709.5294871}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.151, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059709.5294871}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059709.6299465, "x": -88.23571083416394, "y": 40.09283534200755, "z": 202.6145956225352, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": 5.23, "front_wheel_angle": 0.2593721743722212, "heading_rate": 0.5845978938849854, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059709.629641}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.23, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059709.629641}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059709.7297463, "x": -88.23571083416394, "y": 40.09283534200755, "z": 202.6145956225352, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": 5.251, "front_wheel_angle": 0.2605044868335176, "heading_rate": 0.5872689708311999, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059709.7295487}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.251, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059709.7295487}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059709.829765, "x": -88.23571083416394, "y": 40.09283534200755, "z": 202.6145956225352, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": 5.277, "front_wheel_angle": 0.2619075888437103, "heading_rate": 0.5905810673543206, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059709.8295794}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059709.8295794}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059709.9297023, "x": -88.23571083416394, "y": 40.09283534200755, "z": 202.6145956225352, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": 5.278, "front_wheel_angle": 0.261961580674017, "heading_rate": 0.5990874125558331, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059709.9295516}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.278, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059709.9295516}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059710.0298119, "x": -88.23571083416394, "y": 40.09283534200755, "z": 202.6145956225352, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": 5.267, "front_wheel_angle": 0.2613677780295571, "heading_rate": 0.5893065212397378, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059710.029593}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.267, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059710.029593}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059710.1296592, "x": -88.23573990220534, "y": 40.09282857932728, "z": 202.5796723225231, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": 5.216, "front_wheel_angle": 0.2586177760538976, "heading_rate": 0.5910861303945435, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059710.1295617}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.216, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059710.1295617}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059710.2297113, "x": -88.23573990220534, "y": 40.09282857932728, "z": 202.5796723225231, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": 5.104, "front_wheel_angle": 0.2525962447813817, "heading_rate": 0.568647008908426, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059710.2295437}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.104, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059710.2295437}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059710.3299334, "x": -88.23573990220534, "y": 40.09282857932728, "z": 202.5796723225231, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": 4.939, "front_wheel_angle": 0.24376900683115624, "heading_rate": 0.5557228643985883, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059710.3296034}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.939, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059710.3296034}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059710.4298286, "x": -88.23573990220534, "y": 40.09282857932728, "z": 202.5796723225231, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": 4.669, "front_wheel_angle": 0.22943475063214938, "heading_rate": 0.5145336818094802, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059710.4295654}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.669, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059710.4295654}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059710.5297134, "x": -88.23573990220534, "y": 40.09282857932728, "z": 202.5796723225231, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": 4.249, "front_wheel_angle": 0.20740123757150272, "heading_rate": 0.46359724627465887, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059710.5295506}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.249, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059710.5295506}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059710.6300101, "x": -88.23576616645352, "y": 40.092815980489256, "z": 202.5833585533877, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": 3.702, "front_wheel_angle": 0.17916763000178287, "heading_rate": 0.4046670460014454, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059710.6296065}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.702, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059710.6296065}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059710.729662, "x": -88.23576616645352, "y": 40.092815980489256, "z": 202.5833585533877, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": 3.03, "front_wheel_angle": 0.14516063724986564, "heading_rate": 0.32207240799399, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059710.7295613}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.03, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059710.7295613}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059710.8297813, "x": -88.23576616645352, "y": 40.092815980489256, "z": 202.5833585533877, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": 2.287, "front_wheel_angle": 0.10837900554968079, "heading_rate": 0.24311195177944667, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059710.8296027}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.287, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059710.8296027}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059710.9302263, "x": -88.23576616645352, "y": 40.092815980489256, "z": 202.5833585533877, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": 1.489, "front_wheel_angle": 0.06976960853074922, "heading_rate": 0.15614491196394106, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059710.9296446}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.489, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059710.9296446}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059711.0298574, "x": -88.23576616645352, "y": 40.092815980489256, "z": 202.5833585533877, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": 0.724, "front_wheel_angle": 0.033570587593344664, "heading_rate": 0.07398799731846027, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059711.029604}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.724, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059711.029604}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059711.1299994, "x": -88.23579056817064, "y": 40.09279991612189, "z": 202.5744506868545, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": 0.277, "front_wheel_angle": 0.012767505289246275, "heading_rate": 0.02852894480757994, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059711.1296148}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059711.1296148}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059711.229714, "x": -88.23579056817064, "y": 40.09279991612189, "z": 202.5744506868545, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": -0.099, "front_wheel_angle": -0.004552409487872706, "heading_rate": -0.010171860218238292, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059711.2295578}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.099, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059711.2295578}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059711.329744, "x": -88.23579056817064, "y": 40.09279991612189, "z": 202.5744506868545, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": -0.136, "front_wheel_angle": -0.006256860838359406, "heading_rate": -0.01398035587194255, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059711.3295429}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.136, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059711.3295429}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059711.4296536, "x": -88.23579056817064, "y": 40.09279991612189, "z": 202.5744506868545, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.183278816221561, "steering_wheel_angle": -0.007, "front_wheel_angle": -0.00032149905694411315, "heading_rate": -0.000729652181719544, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059711.4295313}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.007, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059711.4295313}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059711.5296776, "x": -88.23579056817064, "y": 40.09279991612189, "z": 202.5744506868545, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": -0.201, "front_wheel_angle": -0.009255201596281284, "heading_rate": -0.020680181549608854, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059711.5295355}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.201, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059711.5295355}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059711.6296623, "x": -88.2358159833425, "y": 40.092783503888114, "z": 202.58426522402453, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": -0.622, "front_wheel_angle": -0.028801472541920926, "heading_rate": -0.06437109033430762, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059711.6295333}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.622, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059711.6295333}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059711.7296572, "x": -88.2358159833425, "y": 40.092783503888114, "z": 202.58426522402453, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": -1.13, "front_wheel_angle": -0.052686120867084074, "heading_rate": -0.11782959636471074, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059711.729536}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059711.729536}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059711.829752, "x": -88.2358159833425, "y": 40.092783503888114, "z": 202.58426522402453, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": -1.685, "front_wheel_angle": -0.07917010803023199, "heading_rate": -0.174786979727318, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059711.8295505}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.685, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059711.8295505}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059711.9297276, "x": -88.2358159833425, "y": 40.092783503888114, "z": 202.58426522402453, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.183278816221561, "steering_wheel_angle": -2.111, "front_wheel_angle": -0.09978614289946863, "heading_rate": -0.2272224428002244, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059711.9294894}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.111, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059711.9294894}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059712.029905, "x": -88.2358159833425, "y": 40.092783503888114, "z": 202.58426522402453, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.183278816221561, "steering_wheel_angle": -2.679, "front_wheel_angle": -0.1276809219542445, "heading_rate": -0.2913608613501227, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059712.0295732}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.679, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059712.0295732}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059712.1298952, "x": -88.2358159833425, "y": 40.092783503888114, "z": 202.58426522402453, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": -3.188, "front_wheel_angle": -0.1530913298062782, "heading_rate": -0.34476104079418735, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059712.1295688}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.188, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059712.1295688}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059712.229743, "x": -88.23584372198779, "y": 40.09276857617281, "z": 202.5976922813036, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": -3.54, "front_wheel_angle": -0.1709026450568797, "heading_rate": -0.38022899144091277, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059712.2295418}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.54, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059712.2295418}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059712.329778, "x": -88.23584372198779, "y": 40.09276857617281, "z": 202.5976922813036, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": -3.73, "front_wheel_angle": -0.1806005492211003, "heading_rate": -0.40226866442075293, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059712.3295844}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.73, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059712.3295844}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059712.429736, "x": -88.23584372198779, "y": 40.09276857617281, "z": 202.5976922813036, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": -3.728, "front_wheel_angle": -0.18049815454550427, "heading_rate": -0.40773819164508, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059712.4295883}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.728, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059712.4295883}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059712.5296595, "x": -88.23584372198779, "y": 40.09276857617281, "z": 202.5976922813036, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": -3.773, "front_wheel_angle": -0.1828036498406488, "heading_rate": -0.4072862152597772, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059712.52956}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.773, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059712.52956}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059712.6297488, "x": -88.23587429748856, "y": 40.09275760823508, "z": 202.6433244120557, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": -3.936, "front_wheel_angle": -0.19118315641009465, "heading_rate": -0.4082632771462145, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059712.6295507}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.936, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059712.6295507}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059712.7297993, "x": -88.23587429748856, "y": 40.09275760823508, "z": 202.6433244120557, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": -4.172, "front_wheel_angle": -0.2033957435807983, "heading_rate": -0.4414991189648027, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059712.7295551}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.172, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059712.7295551}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059712.8297718, "x": -88.23587429748856, "y": 40.09275760823508, "z": 202.6433244120557, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": -4.416, "front_wheel_angle": -0.21612435094898022, "heading_rate": -0.4699816501760678, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059712.8296254}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059712.8296254}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059712.9298298, "x": -88.23587429748856, "y": 40.09275760823508, "z": 202.6433244120557, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": -4.684, "front_wheel_angle": -0.23022755825587246, "heading_rate": -0.4944025030507603, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059712.9295967}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.684, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059712.9295967}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059713.029721, "x": -88.23587429748856, "y": 40.09275760823508, "z": 202.6433244120557, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": -4.98, "front_wheel_angle": -0.24595761402836322, "heading_rate": -0.5050226601495794, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059713.029549}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.98, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059713.029549}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059713.129874, "x": -88.23590654170096, "y": 40.09275228373723, "z": 202.67847201075884, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": -5.203, "front_wheel_angle": -0.2579176041802392, "heading_rate": -0.5471644102455224, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059713.1296034}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.203, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059713.1296034}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059713.2299762, "x": -88.23590654170096, "y": 40.09275228373723, "z": 202.67847201075884, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": -5.434, "front_wheel_angle": -0.27040838484357604, "heading_rate": -0.5489816808889315, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059713.2296345}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.434, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059713.2296345}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059713.3296573, "x": -88.23590654170096, "y": 40.09275228373723, "z": 202.67847201075884, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": -5.434, "front_wheel_angle": -0.27040838484357604, "heading_rate": -0.5489816808889315, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059713.329555}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.434, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059713.329555}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059713.4299805, "x": -88.23590654170096, "y": 40.09275228373723, "z": 202.67847201075884, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": -5.953, "front_wheel_angle": -0.29886337529158524, "heading_rate": -0.6005373380930149, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059713.4296176}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.953, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059713.4296176}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059713.529706, "x": -88.23590654170096, "y": 40.09275228373723, "z": 202.67847201075884, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": -5.953, "front_wheel_angle": -0.29886337529158524, "heading_rate": -0.6101651912087346, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059713.5295475}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.953, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059713.5295475}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059713.6296463, "x": -88.23593725800362, "y": 40.0927529330025, "z": 202.67034841656988, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": -6.58, "front_wheel_angle": -0.3340005092982597, "heading_rate": -0.6655368574331437, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059713.6295338}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.58, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059713.6295338}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059713.7296867, "x": -88.23593725800362, "y": 40.0927529330025, "z": 202.67034841656988, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": -6.854, "front_wheel_angle": -0.3496317004970785, "heading_rate": -0.6864944817896442, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059713.7295582}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.854, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059713.7295582}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059713.8297904, "x": -88.23593725800362, "y": 40.0927529330025, "z": 202.67034841656988, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": -7.043, "front_wheel_angle": -0.36051605742192555, "heading_rate": -0.6862435014526216, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059713.8295994}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.043, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059713.8295994}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059713.9296587, "x": -88.23593725800362, "y": 40.0927529330025, "z": 202.67034841656988, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": -7.285, "front_wheel_angle": -0.37457811429832943, "heading_rate": -0.7033509637759499, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059713.9295337}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.285, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059713.9295337}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059714.029815, "x": -88.23593725800362, "y": 40.0927529330025, "z": 202.67034841656988, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": -7.522, "front_wheel_angle": -0.3884900851756995, "heading_rate": -0.7578278103627079, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059714.0295537}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.522, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059714.0295537}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059714.1296306, "x": -88.23596439034907, "y": 40.09276056935752, "z": 202.6925144873159, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": -7.685, "front_wheel_angle": -0.39814114226102015, "heading_rate": -0.765630355989676, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059714.1295278}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.685, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059714.1295278}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059714.2300348, "x": -88.23596439034907, "y": 40.09276056935752, "z": 202.6925144873159, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": -7.9, "front_wheel_angle": -0.4109772105554259, "heading_rate": -0.7796618237050504, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059714.2295847}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.9, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059714.2295847}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059714.329892, "x": -88.23596439034907, "y": 40.09276056935752, "z": 202.6925144873159, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9592068162215615, "steering_wheel_angle": -8.153, "front_wheel_angle": -0.42624102169006567, "heading_rate": -0.7680324231233971, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059714.3295896}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.153, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059714.3295896}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059714.429686, "x": -88.23596439034907, "y": 40.09276056935752, "z": 202.6925144873159, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": -8.417, "front_wheel_angle": -0.44235799087128125, "heading_rate": -0.8474151019603021, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059714.4295404}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.417, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059714.4295404}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059714.529727, "x": -88.23596439034907, "y": 40.09276056935752, "z": 202.6925144873159, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": -8.674, "front_wheel_angle": -0.458240318043019, "heading_rate": -0.86705691636442, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059714.529577}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059714.529577}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059714.6296976, "x": -88.23598572979783, "y": 40.09277402190229, "z": 202.6915506382929, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": -8.903, "front_wheel_angle": -0.4725582426346963, "heading_rate": -0.8985734229905621, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059714.6295545}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.903, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059714.6295545}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059714.7304118, "x": -88.23598572979783, "y": 40.09277402190229, "z": 202.6915506382929, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": -9.102, "front_wheel_angle": -0.4851317573426021, "heading_rate": -0.9081000013511017, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059714.7296412}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.102, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059714.7296412}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059714.8297122, "x": -88.23598572979783, "y": 40.09277402190229, "z": 202.6915506382929, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9483428162215617, "steering_wheel_angle": -9.26, "front_wheel_angle": -0.49520426166207604, "heading_rate": -0.8966366192686068, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059714.82957}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.25, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.26, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059714.82957}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059714.9301481, "x": -88.23598572979783, "y": 40.09277402190229, "z": 202.6915506382929, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9376068162215616, "steering_wheel_angle": -9.408, "front_wheel_angle": -0.5047129872776875, "heading_rate": -0.899869537638749, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059714.9296257}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.17, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059714.9296257}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059715.0298417, "x": -88.23598572979783, "y": 40.09277402190229, "z": 202.6915506382929, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9269988162215617, "steering_wheel_angle": -9.623, "front_wheel_angle": -0.5186568311505255, "heading_rate": -0.9119097611316795, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059715.0296009}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.09, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.623, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059715.0296009}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059715.1300771, "x": -88.23599872142326, "y": 40.092791117302106, "z": 202.71680899918925, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9376068162215616, "steering_wheel_angle": -9.831, "front_wheel_angle": -0.532298266447191, "heading_rate": -0.9594395281959345, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059715.1296248}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.17, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.831, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059715.1296248}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059715.229958, "x": -88.23599872142326, "y": 40.092791117302106, "z": 202.71680899918925, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9443018162215617, "steering_wheel_angle": -9.905, "front_wheel_angle": -0.537188382409465, "heading_rate": -0.9818327286312268, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059715.2296143}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.905, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059715.2296143}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059715.330266, "x": -88.23599872142326, "y": 40.092791117302106, "z": 202.71680899918925, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.934942816221562, "steering_wheel_angle": -9.902, "front_wheel_angle": -0.5369897519967172, "heading_rate": -0.9651102258420375, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059715.3296075}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.902, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059715.3296075}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059715.429719, "x": -88.23599872142326, "y": 40.092791117302106, "z": 202.71680899918925, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9309618162215614, "steering_wheel_angle": -9.821, "front_wheel_angle": -0.531638941682323, "heading_rate": -0.9465067822393247, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059715.4295437}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.821, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059715.4295437}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059715.529717, "x": -88.23599872142326, "y": 40.092791117302106, "z": 202.71680899918925, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8984868162215616, "steering_wheel_angle": -9.702, "front_wheel_angle": -0.5238201221957497, "heading_rate": -0.8732374360173126, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059715.529545}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.702, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059715.529545}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059715.6297584, "x": -88.23600172864423, "y": 40.09280961276142, "z": 202.7688228372016, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9113268162215618, "steering_wheel_angle": -9.588, "front_wheel_angle": -0.5163761886015995, "heading_rate": -0.8804715277448361, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059715.629577}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.588, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059715.629577}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059715.729839, "x": -88.23600172864423, "y": 40.09280961276142, "z": 202.7688228372016, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8959428162215617, "steering_wheel_angle": -9.422, "front_wheel_angle": -0.5056162140018229, "heading_rate": -0.8325886120276396, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059715.7295861}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.422, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059715.7295861}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059715.8300369, "x": -88.23600172864423, "y": 40.09280961276142, "z": 202.7688228372016, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9100338162215618, "steering_wheel_angle": -9.182, "front_wheel_angle": -0.490221718047345, "heading_rate": -0.825525387541533, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059715.8296354}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.96, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.182, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059715.8296354}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059715.9300408, "x": -88.23600172864423, "y": 40.09280961276142, "z": 202.7688228372016, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9010388162215617, "steering_wheel_angle": -8.908, "front_wheel_angle": -0.47287264756032854, "heading_rate": -0.777369490509784, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059715.929631}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.908, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059715.929631}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059716.0296786, "x": -88.23600172864423, "y": 40.09280961276142, "z": 202.7688228372016, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9023178162215615, "steering_wheel_angle": -8.848, "front_wheel_angle": -0.46910487004645135, "heading_rate": -0.7721395330717867, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059716.029551}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.9, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.848, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059716.029551}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059716.1297047, "x": -88.23599633100704, "y": 40.092827405027265, "z": 202.78580239285048, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.919126816221562, "steering_wheel_angle": -8.843, "front_wheel_angle": -0.4687913875787878, "heading_rate": -0.7972573548349003, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059716.1295362}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.843, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059716.1295362}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059716.2296877, "x": -88.23599633100704, "y": 40.092827405027265, "z": 202.78580239285048, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9204338162215615, "steering_wheel_angle": -8.784, "front_wheel_angle": -0.4650980569801828, "heading_rate": -0.7919258138236385, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059716.229566}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.04, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.784, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059716.229566}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059716.3297372, "x": -88.23599633100704, "y": 40.092827405027265, "z": 202.78580239285048, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.932286816221562, "steering_wheel_angle": -8.536, "front_wheel_angle": -0.4496880031188943, "heading_rate": -0.778682984722214, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059716.3295426}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.536, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059716.3295426}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059716.4297192, "x": -88.23599633100704, "y": 40.092827405027265, "z": 202.78580239285048, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9389418162215613, "steering_wheel_angle": -8.144, "front_wheel_angle": -0.4256950291709012, "heading_rate": -0.7403511648573904, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059716.4295588}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.144, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059716.4295588}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059716.5298707, "x": -88.23599633100704, "y": 40.092827405027265, "z": 202.78580239285048, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9619428162215615, "steering_wheel_angle": -7.705, "front_wheel_angle": -0.3993300604016482, "heading_rate": -0.7170766814814091, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059716.5295749}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.35, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.705, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059716.5295749}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059716.6300302, "x": -88.23598425441998, "y": 40.09284389457632, "z": 202.84737359163915, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.986926816221562, "steering_wheel_angle": -7.377, "front_wheel_angle": -0.3799618026496381, "heading_rate": -0.7066949191574112, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059716.629586}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.53, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.377, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059716.629586}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059716.730144, "x": -88.23598425441998, "y": 40.09284389457632, "z": 202.84737359163915, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": -7.25, "front_wheel_angle": -0.3725354852322397, "heading_rate": -0.6991351347881299, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059716.729621}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.25, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059716.729621}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059716.829924, "x": -88.23598425441998, "y": 40.09284389457632, "z": 202.84737359163915, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.021246816221561, "steering_wheel_angle": -7.141, "front_wheel_angle": -0.3661934295249823, "heading_rate": -0.7145504233518372, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059716.8296063}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.141, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059716.8296063}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059716.9297013, "x": -88.23598425441998, "y": 40.09284389457632, "z": 202.84737359163915, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.038838816221562, "steering_wheel_angle": -7.079, "front_wheel_angle": -0.3625989288291922, "heading_rate": -0.7246615284549628, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059716.9295743}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.079, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059716.9295743}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059717.029682, "x": -88.23598425441998, "y": 40.09284389457632, "z": 202.84737359163915, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": -6.874, "front_wheel_angle": -0.35077948706045686, "heading_rate": -0.6889438698769076, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059717.0295632}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.874, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059717.0295632}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059717.1296444, "x": -88.23596400703966, "y": 40.09285915642824, "z": 202.89752221238493, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": -6.589, "front_wheel_angle": -0.3345112065427989, "heading_rate": -0.6883578184397848, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059717.1295316}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.589, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059717.1295316}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059717.2296267, "x": -88.23596400703966, "y": 40.09285915642824, "z": 202.89752221238493, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": -6.484, "front_wheel_angle": -0.3285644649413842, "heading_rate": -0.6964923751503908, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059717.2295277}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.484, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059717.2295277}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059717.3298848, "x": -88.23596400703966, "y": 40.09285915642824, "z": 202.89752221238493, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": -6.479, "front_wheel_angle": -0.32828190591174417, "heading_rate": -0.6958480844688624, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059717.3295634}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.479, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059717.3295634}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059717.4297848, "x": -88.23596400703966, "y": 40.09285915642824, "z": 202.89752221238493, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.183278816221561, "steering_wheel_angle": -6.379, "front_wheel_angle": -0.3226424472246247, "heading_rate": -0.7587601734935966, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059717.4295526}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.379, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059717.4295526}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059717.5299282, "x": -88.23596400703966, "y": 40.09285915642824, "z": 202.89752221238493, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": -6.106, "front_wheel_angle": -0.3073587321795233, "heading_rate": -0.6484743860001454, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059717.529579}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.106, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059717.529579}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059717.6300232, "x": -88.23593583575034, "y": 40.09287126458825, "z": 202.85687539830008, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": -5.747, "front_wheel_angle": -0.287502972107054, "heading_rate": -0.6514539656925331, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059717.6295917}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.747, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059717.6295917}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059717.7296176, "x": -88.23593583575034, "y": 40.09287126458825, "z": 202.85687539830008, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1966388162215615, "steering_wheel_angle": -5.382, "front_wheel_angle": -0.2675874463859847, "heading_rate": -0.6307879868463371, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059717.7295256}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.382, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059717.7295256}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059717.829644, "x": -88.23593583575034, "y": 40.09287126458825, "z": 202.85687539830008, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": -5.01, "front_wheel_angle": -0.2475610497902799, "heading_rate": -0.5647283705909331, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059717.8295276}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.01, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059717.8295276}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059717.9297042, "x": -88.23593583575034, "y": 40.09287126458825, "z": 202.85687539830008, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.237486816221562, "steering_wheel_angle": -4.605, "front_wheel_angle": -0.2260567297857441, "heading_rate": -0.5507127948816797, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059717.929566}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.605, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059717.929566}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059718.029714, "x": -88.23593583575034, "y": 40.09287126458825, "z": 202.85687539830008, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.237486816221562, "steering_wheel_angle": -4.173, "front_wheel_angle": -0.20344769662203524, "heading_rate": -0.4939964116429131, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059718.0295384}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.173, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059718.0295384}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059718.1297648, "x": -88.23590143944946, "y": 40.09287750200122, "z": 202.7934523872838, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.2531018162215615, "steering_wheel_angle": -3.798, "front_wheel_angle": -0.1840859444839915, "heading_rate": -0.4523930775691047, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059718.1295583}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.798, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059718.1295583}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059718.2297819, "x": -88.23590143944946, "y": 40.09287750200122, "z": 202.7934523872838, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": -3.798, "front_wheel_angle": -0.1840859444839915, "heading_rate": -0.4640301985355125, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059718.2295601}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.798, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059718.2295601}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059718.3297205, "x": -88.23590143944946, "y": 40.09287750200122, "z": 202.7934523872838, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": -3.347, "front_wheel_angle": -0.16111210282827157, "heading_rate": -0.41011090894931795, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059718.3295393}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.347, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059718.3295393}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059718.4296415, "x": -88.23590143944946, "y": 40.09287750200122, "z": 202.7934523872838, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.324461816221562, "steering_wheel_angle": -3.164, "front_wheel_angle": -0.15188413731163197, "heading_rate": -0.3958112061782983, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059718.4295514}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.164, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059718.4295514}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059718.5296812, "x": -88.23590143944946, "y": 40.09287750200122, "z": 202.7934523872838, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.340958816221562, "steering_wheel_angle": -3.086, "front_wheel_angle": -0.1479670324141942, "heading_rate": -0.39069092835846125, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059718.5295267}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.086, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059718.5295267}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059718.630125, "x": -88.23586277409105, "y": 40.0928779748711, "z": 202.86259552100893, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": -3.145, "front_wheel_angle": -0.15092908838302335, "heading_rate": -0.4081361327473389, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059718.6295614}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.145, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059718.6295614}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059718.729629, "x": -88.23586277409105, "y": 40.0928779748711, "z": 202.86259552100893, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.400926816221562, "steering_wheel_angle": -3.126, "front_wheel_angle": -0.14997460846056065, "heading_rate": -0.41496015773421785, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059718.7295265}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.126, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059718.7295265}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059718.8296595, "x": -88.23586277409105, "y": 40.0928779748711, "z": 202.86259552100893, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": -3.087, "front_wheel_angle": -0.1480171912102084, "heading_rate": -0.41470585505606167, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059718.8295279}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.087, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059718.8295279}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059718.9298956, "x": -88.23586277409105, "y": 40.0928779748711, "z": 202.86259552100893, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": -3.088, "front_wheel_angle": -0.14806735157385226, "heading_rate": -0.4195096850656629, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059718.9295444}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.088, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059718.9295444}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059719.0299277, "x": -88.23586277409105, "y": 40.0928779748711, "z": 202.86259552100893, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.464913816221562, "steering_wheel_angle": -3.086, "front_wheel_angle": -0.1479670324141942, "heading_rate": -0.4285372925064493, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059719.029621}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.086, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059719.029621}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059719.1297154, "x": -88.23582136526615, "y": 40.09287260660568, "z": 202.9193912080963, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.480753816221561, "steering_wheel_angle": -3.077, "front_wheel_angle": -0.1475156737691783, "heading_rate": -0.4318544911316457, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059719.129548}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.077, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059719.129548}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059719.229901, "x": -88.23582136526615, "y": 40.09287260660568, "z": 202.9193912080963, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.496721816221561, "steering_wheel_angle": -2.971, "front_wheel_angle": -0.1422091889038195, "heading_rate": -0.42057850553237786, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059719.22955}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.971, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059719.22955}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059719.330049, "x": -88.23582136526615, "y": 40.09287260660568, "z": 202.9193912080963, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.496721816221561, "steering_wheel_angle": -2.797, "front_wheel_angle": -0.13353624115011803, "heading_rate": -0.3946110601426156, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059719.3295815}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.797, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059719.3295815}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059719.429674, "x": -88.23582136526615, "y": 40.09287260660568, "z": 202.9193912080963, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.531078816221561, "steering_wheel_angle": -2.655, "front_wheel_angle": -0.12649258919959822, "heading_rate": -0.38201149834018344, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059719.4295292}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.655, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059719.4295292}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059719.5296712, "x": -88.23582136526615, "y": 40.09287260660568, "z": 202.9193912080963, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.547446816221561, "steering_wheel_angle": -2.579, "front_wheel_angle": -0.12273525005815494, "heading_rate": -0.3744025447190987, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059719.5295014}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.579, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059719.5295014}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059719.6296444, "x": -88.23577920811432, "y": 40.09286050016321, "z": 202.91855398403794, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.563942816221561, "steering_wheel_angle": -2.471, "front_wheel_angle": -0.11741072162538303, "heading_rate": -0.3616925105846577, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059719.6295493}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.471, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059719.6295493}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059719.729977, "x": -88.23577920811432, "y": 40.09286050016321, "z": 202.91855398403794, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.580566816221562, "steering_wheel_angle": -2.284, "front_wheel_angle": -0.10823216021216073, "heading_rate": -0.3365813153839969, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059719.729745}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.284, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059719.729745}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059719.829792, "x": -88.23577920811432, "y": 40.09286050016321, "z": 202.91855398403794, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.580566816221562, "steering_wheel_angle": -1.976, "front_wheel_angle": -0.09322517528152095, "heading_rate": -0.2896190533542774, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059719.829542}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.976, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059719.829542}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059719.9298494, "x": -88.23577920811432, "y": 40.09286050016321, "z": 202.91855398403794, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": -1.513, "front_wheel_angle": -0.07091786744269439, "heading_rate": -0.22476549902114049, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059719.9295523}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.513, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059719.9295523}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059720.0299056, "x": -88.23577920811432, "y": 40.09286050016321, "z": 202.91855398403794, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.633341816221561, "steering_wheel_angle": -1.006, "front_wheel_angle": -0.04682516239905654, "heading_rate": -0.1497304755333146, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059720.0295117}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.006, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059720.0295117}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059720.1296566, "x": -88.23573856854428, "y": 40.092842498873694, "z": 202.90655331567817, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.633341816221561, "steering_wheel_angle": -0.479, "front_wheel_angle": -0.022137485492654298, "heading_rate": -0.0707477415651437, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059720.1295557}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.479, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059720.1295557}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059720.2296755, "x": -88.23573856854428, "y": 40.092842498873694, "z": 202.90655331567817, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.650493816221561, "steering_wheel_angle": 0.109, "front_wheel_angle": 0.0050129081195356496, "heading_rate": 0.016174596839816983, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059720.2295325}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.26, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.109, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059720.2295325}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059720.329659, "x": -88.23573856854428, "y": 40.092842498873694, "z": 202.90655331567817, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.667773816221562, "steering_wheel_angle": 0.77, "front_wheel_angle": 0.03572569838533924, "heading_rate": 0.11643716822983842, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059720.3295262}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.77, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059720.3295262}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059720.4297054, "x": -88.23573856854428, "y": 40.092842498873694, "z": 202.90655331567817, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.667773816221562, "steering_wheel_angle": 1.053, "front_wheel_angle": 0.049044282253804486, "heading_rate": 0.1599053053059059, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059720.4295335}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.053, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059720.4295335}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059720.5296388, "x": -88.23573856854428, "y": 40.092842498873694, "z": 202.90655331567817, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.687366816221561, "steering_wheel_angle": 0.859, "front_wheel_angle": 0.03990306659718107, "heading_rate": 0.13146933629897406, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059720.5295475}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.859, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059720.5295475}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059720.6297438, "x": -88.2356980680886, "y": 40.09282218521887, "z": 202.92476210278824, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.704918816221562, "steering_wheel_angle": 0.725, "front_wheel_angle": 0.0336174091043244, "heading_rate": 0.11179373867085497, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059720.6295636}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.51, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.725, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059720.6295636}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059720.7302315, "x": -88.2356980680886, "y": 40.09282218521887, "z": 202.92476210278824, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.667773816221562, "steering_wheel_angle": 0.776, "front_wheel_angle": 0.03600699922063998, "heading_rate": 0.1173547735101631, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059720.7296238}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.776, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059720.7296238}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059720.829718, "x": -88.2356980680886, "y": 40.09282218521887, "z": 202.92476210278824, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.704918816221562, "steering_wheel_angle": 1.035, "front_wheel_angle": 0.048194065264014, "heading_rate": 0.16033176709920385, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059720.8295722}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.51, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.035, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059720.8295722}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059720.9296858, "x": -88.2356980680886, "y": 40.09282218521887, "z": 202.92476210278824, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.667773816221562, "steering_wheel_angle": 1.264, "front_wheel_angle": 0.0590425348620793, "heading_rate": 0.192573331681942, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059720.9295576}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.264, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059720.9295576}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059721.0296876, "x": -88.2356980680886, "y": 40.09282218521887, "z": 202.92476210278824, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.633341816221561, "steering_wheel_angle": 1.395, "front_wheel_angle": 0.06527978326702322, "heading_rate": 0.20888611104809524, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059721.0295632}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.395, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059721.0295632}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059721.129862, "x": -88.23565568742674, "y": 40.0928039966323, "z": 202.91730908572666, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.667773816221562, "steering_wheel_angle": 1.514, "front_wheel_angle": 0.07096572857535413, "heading_rate": 0.2315819274649953, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059721.1295834}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.514, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059721.1295834}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059721.2296214, "x": -88.23565568742674, "y": 40.0928039966323, "z": 202.91730908572666, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.722598816221561, "steering_wheel_angle": 1.53, "front_wheel_angle": 0.07173169199718055, "heading_rate": 0.24110712653851946, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059721.2295241}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.59, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.53, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059721.2295241}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059721.3297098, "x": -88.23565568742674, "y": 40.0928039966323, "z": 202.91730908572666, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.687366816221561, "steering_wheel_angle": 1.644, "front_wheel_angle": 0.07719931527620957, "heading_rate": 0.25472115736221673, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059721.329557}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.644, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059721.329557}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059721.4297676, "x": -88.23565568742674, "y": 40.0928039966323, "z": 202.91730908572666, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.650493816221561, "steering_wheel_angle": 1.827, "front_wheel_angle": 0.08601378972935374, "heading_rate": 0.2782153205517945, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059721.4295716}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.26, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.827, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059721.4295716}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059721.5297318, "x": -88.23565568742674, "y": 40.0928039966323, "z": 202.91730908572666, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.633341816221561, "steering_wheel_angle": 1.932, "front_wheel_angle": 0.09109238266839095, "heading_rate": 0.2918763887349566, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059721.5295615}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.932, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059721.5295615}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059721.629751, "x": -88.23561157611893, "y": 40.092790494241086, "z": 202.92384934442512, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": 1.995, "front_wheel_angle": 0.09414700163303956, "heading_rate": 0.29877025184714473, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059721.6295662}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.995, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059721.6295662}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059721.7296736, "x": -88.23561157611893, "y": 40.092790494241086, "z": 202.92384934442512, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.633341816221561, "steering_wheel_angle": 2.056, "front_wheel_angle": 0.0971100179987963, "heading_rate": 0.3112759510703574, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059721.7295597}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.056, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059721.7295597}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059721.8296459, "x": -88.23561157611893, "y": 40.092790494241086, "z": 202.92384934442512, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.650493816221561, "steering_wheel_angle": 2.107, "front_wheel_angle": 0.09959136957999266, "heading_rate": 0.3224044002213664, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059721.8295276}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.26, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.107, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059721.8295276}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059721.9296744, "x": -88.23561157611893, "y": 40.092790494241086, "z": 202.92384934442512, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.633341816221561, "steering_wheel_angle": 2.158, "front_wheel_angle": 0.10207645070030852, "heading_rate": 0.3273037408715994, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059721.929562}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.158, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059721.929562}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059722.029654, "x": -88.23561157611893, "y": 40.092790494241086, "z": 202.92384934442512, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": 2.194, "front_wheel_angle": 0.10383288023003942, "heading_rate": 0.3264630175427261, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059722.0295506}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.194, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059722.0295506}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059722.129798, "x": -88.23556640942746, "y": 40.09278235164957, "z": 202.9176578257745, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.580566816221562, "steering_wheel_angle": 2.222, "front_wheel_angle": 0.10520028647873099, "heading_rate": 0.32708183191186935, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059722.1295216}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.222, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059722.1295216}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059722.2297003, "x": -88.23556640942746, "y": 40.09278235164957, "z": 202.9176578257745, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.563942816221561, "steering_wheel_angle": 2.235, "front_wheel_angle": 0.10583553953941618, "heading_rate": 0.32575193579868233, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059722.2295377}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.235, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059722.2295377}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059722.3297412, "x": -88.23556640942746, "y": 40.09278235164957, "z": 202.9176578257745, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": 2.237, "front_wheel_angle": 0.10593329252619935, "heading_rate": 0.33311613735759554, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059722.329596}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.237, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059722.329596}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059722.4297838, "x": -88.23556640942746, "y": 40.09278235164957, "z": 202.9176578257745, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.580566816221562, "steering_wheel_angle": 2.237, "front_wheel_angle": 0.10593329252619935, "heading_rate": 0.32937792633986696, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059722.429549}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.237, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059722.429549}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059722.5296533, "x": -88.23556640942746, "y": 40.09278235164957, "z": 202.9176578257745, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.563942816221561, "steering_wheel_angle": 2.276, "front_wheel_angle": 0.10784063672633207, "heading_rate": 0.33197109866215985, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059722.529554}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.276, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059722.529554}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059722.630082, "x": -88.23552157109941, "y": 40.092779650293416, "z": 202.93609318016078, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.547446816221561, "steering_wheel_angle": 2.352, "front_wheel_angle": 0.11156388043538759, "heading_rate": 0.34002569078108125, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059722.629631}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.352, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059722.629631}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059722.729739, "x": -88.23552157109941, "y": 40.092779650293416, "z": 202.93609318016078, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.514838816221562, "steering_wheel_angle": 2.412, "front_wheel_angle": 0.11450925972953352, "heading_rate": 0.34189231411210225, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059722.7296386}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.412, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059722.7296386}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059722.8299909, "x": -88.23552157109941, "y": 40.092779650293416, "z": 202.93609318016078, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.514838816221562, "steering_wheel_angle": 2.442, "front_wheel_angle": 0.11598393669103603, "heading_rate": 0.34633476551759823, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059722.8298054}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.442, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059722.8298054}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059722.9311626, "x": -88.23552157109941, "y": 40.092779650293416, "z": 202.93609318016078, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.531078816221561, "steering_wheel_angle": 2.441, "front_wheel_angle": 0.11593475939007289, "heading_rate": 0.34982587572503526, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059722.9305718}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.441, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059722.9305718}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059723.0297139, "x": -88.23552157109941, "y": 40.092779650293416, "z": 202.93609318016078, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.531078816221561, "steering_wheel_angle": 2.442, "front_wheel_angle": 0.11598393669103603, "heading_rate": 0.3499756040512918, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059723.02956}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.442, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059723.02956}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059723.1303883, "x": -88.2354782801633, "y": 40.092782364739435, "z": 202.93763802654976, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.496721816221561, "steering_wheel_angle": 2.443, "front_wheel_angle": 0.11603311546939078, "heading_rate": 0.3423852465810539, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059723.1301568}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.443, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059723.1301568}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059723.2296536, "x": -88.2354782801633, "y": 40.092782364739435, "z": 202.93763802654976, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.496721816221561, "steering_wheel_angle": 2.443, "front_wheel_angle": 0.11603311546939078, "heading_rate": 0.3423852465810539, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059723.2295544}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.443, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059723.2295544}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059723.3296423, "x": -88.2354782801633, "y": 40.092782364739435, "z": 202.93763802654976, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.464913816221562, "steering_wheel_angle": 2.441, "front_wheel_angle": 0.11593475939007289, "heading_rate": 0.33481384204632764, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059723.329524}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.441, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059723.329524}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059723.42966, "x": -88.2354782801633, "y": 40.092782364739435, "z": 202.93763802654976, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.464913816221562, "steering_wheel_angle": 2.439, "front_wheel_angle": 0.11583640921978766, "heading_rate": 0.334527253776304, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059723.429544}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.439, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059723.429544}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059723.529636, "x": -88.2354782801633, "y": 40.092782364739435, "z": 202.93763802654976, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.464913816221562, "steering_wheel_angle": 2.44, "front_wheel_angle": 0.11588558356636776, "heading_rate": 0.3346705449389125, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059723.5295208}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.44, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059723.5295208}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059723.629773, "x": -88.23543746966924, "y": 40.09279020765925, "z": 202.95395345718381, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.449201816221562, "steering_wheel_angle": 2.439, "front_wheel_angle": 0.11583640921978766, "heading_rate": 0.33089108797438765, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059723.6295636}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.439, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059723.6295636}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059723.729957, "x": -88.23543746966924, "y": 40.09279020765925, "z": 202.95395345718381, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": 2.444, "front_wheel_angle": 0.11608229572527015, "heading_rate": 0.32795586102715923, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059723.729553}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059723.729553}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059723.8296862, "x": -88.23543746966924, "y": 40.09279020765925, "z": 202.95395345718381, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": 2.447, "front_wheel_angle": 0.11622984535938623, "heading_rate": 0.32472786646296825, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059723.8295505}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.447, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059723.8295505}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059723.9298465, "x": -88.23543746966924, "y": 40.09279020765925, "z": 202.95395345718381, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": 2.495, "front_wheel_angle": 0.11859245109833795, "heading_rate": 0.3313902896184734, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059723.9295764}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.495, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059723.9295764}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059724.029744, "x": -88.23543746966924, "y": 40.09279020765925, "z": 202.95395345718381, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": 2.554, "front_wheel_angle": 0.12150117463826494, "heading_rate": 0.33148952082934907, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059724.0295625}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.554, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059724.0295625}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059724.12968, "x": -88.23540015558618, "y": 40.09280258279178, "z": 202.92723192708178, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": 2.522, "front_wheel_angle": 0.11992291891064037, "heading_rate": 0.3271417563111651, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059724.1295285}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.522, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059724.1295285}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059724.2296777, "x": -88.23540015558618, "y": 40.09280258279178, "z": 202.92723192708178, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": 2.436, "front_wheel_angle": 0.1156888950414671, "heading_rate": 0.3118545173288656, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059724.229544}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.436, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059724.229544}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059724.3297791, "x": -88.23540015558618, "y": 40.09280258279178, "z": 202.92723192708178, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.340958816221562, "steering_wheel_angle": 2.204, "front_wheel_angle": 0.1043211094104051, "heading_rate": 0.2744316678112797, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059724.329575}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.204, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059724.329575}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059724.4297774, "x": -88.23540015558618, "y": 40.09280258279178, "z": 202.92723192708178, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.324461816221562, "steering_wheel_angle": 1.835, "front_wheel_angle": 0.08640018549735992, "heading_rate": 0.2239831012769238, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059724.4295318}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.835, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059724.4295318}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059724.5296779, "x": -88.23540015558618, "y": 40.09280258279178, "z": 202.92723192708178, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3099338162215615, "steering_wheel_angle": 1.368, "front_wheel_angle": 0.06399235906733865, "heading_rate": 0.16370399799156699, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059724.529529}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.54, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.368, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059724.529529}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059724.629715, "x": -88.23536748795622, "y": 40.092818254811064, "z": 202.94187159650178, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": 0.77, "front_wheel_angle": 0.03572569838533924, "heading_rate": 0.08907303756671094, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059724.629535}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.77, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059724.629535}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059724.72978, "x": -88.23536748795622, "y": 40.092818254811064, "z": 202.94187159650178, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": 0.122, "front_wheel_angle": 0.005611737772796137, "heading_rate": 0.01398564954111283, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059724.7295685}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.122, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059724.7295685}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059724.8298633, "x": -88.23536748795622, "y": 40.092818254811064, "z": 202.94187159650178, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.2531018162215615, "steering_wheel_angle": -0.491, "front_wheel_angle": -0.022695714677630163, "heading_rate": -0.055152964261592274, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059724.829583}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.491, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059724.829583}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059724.9296541, "x": -88.23536748795622, "y": 40.092818254811064, "z": 202.94187159650178, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.223742816221561, "steering_wheel_angle": -1.153, "front_wheel_angle": -0.05377545674445793, "heading_rate": -0.127209173432492, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059724.9295297}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.153, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059724.9295297}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059725.0296886, "x": -88.23536748795622, "y": 40.092818254811064, "z": 202.94187159650178, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1966388162215615, "steering_wheel_angle": -1.815, "front_wheel_angle": -0.08543436395348929, "heading_rate": -0.1970454296723387, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059725.0295315}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.815, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059725.0295315}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059725.1297178, "x": -88.23533730123911, "y": 40.09283375587377, "z": 202.9452504754566, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.183278816221561, "steering_wheel_angle": -2.388, "front_wheel_angle": -0.1133304730999011, "heading_rate": -0.2583139087706833, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059725.1295288}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.388, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059725.1295288}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059725.2296572, "x": -88.23533730123911, "y": 40.09283375587377, "z": 202.9452504754566, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": -2.804, "front_wheel_angle": -0.13388425593348913, "heading_rate": -0.2967388879892633, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059725.229527}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.804, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059725.229527}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059725.3298278, "x": -88.23533730123911, "y": 40.09283375587377, "z": 202.9452504754566, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.142353816221561, "steering_wheel_angle": -3.195, "front_wheel_angle": -0.15344359923683543, "heading_rate": -0.3359007183009976, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059725.3295412}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.195, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059725.3295412}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059725.429697, "x": -88.23533730123911, "y": 40.09283375587377, "z": 202.9452504754566, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": -3.707, "front_wheel_angle": -0.17942341273343, "heading_rate": -0.3825855950314196, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059725.4295216}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.707, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059725.4295216}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059725.5297377, "x": -88.23533730123911, "y": 40.09283375587377, "z": 202.9452504754566, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": -4.308, "front_wheel_angle": -0.21047742058170466, "heading_rate": -0.44313942260290823, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059725.529565}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.308, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059725.529565}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059725.6298323, "x": -88.2353068369831, "y": 40.092844450869976, "z": 202.94772043661297, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": -4.921, "front_wheel_angle": -0.242809156820157, "heading_rate": -0.5302245614422767, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059725.6295555}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.921, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059725.6295555}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059725.7298424, "x": -88.2353068369831, "y": 40.092844450869976, "z": 202.94772043661297, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": -5.333, "front_wheel_angle": -0.264934148240788, "heading_rate": -0.5542816393298708, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059725.7295487}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.333, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059725.7295487}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059725.8298986, "x": -88.2353068369831, "y": 40.092844450869976, "z": 202.94772043661297, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": -5.719, "front_wheel_angle": -0.28596563108392126, "heading_rate": -0.5914944300477112, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059725.829578}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.719, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059725.829578}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059725.9296877, "x": -88.2353068369831, "y": 40.092844450869976, "z": 202.94772043661297, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": -6.117, "front_wheel_angle": -0.30797143396841875, "heading_rate": -0.6299717367703768, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059725.929563}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.117, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059725.929563}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059726.0298293, "x": -88.2353068369831, "y": 40.092844450869976, "z": 202.94772043661297, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": -6.37, "front_wheel_angle": -0.32213598618315964, "heading_rate": -0.6505744582650387, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059726.0295806}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.37, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059726.0295806}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059726.130948, "x": -88.23527543896884, "y": 40.09284818927644, "z": 202.88792820987143, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": -6.449, "front_wheel_angle": -0.32658772717099044, "heading_rate": -0.6814027198616847, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059726.129622}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.449, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059726.129622}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059726.2298348, "x": -88.23527543896884, "y": 40.09284818927644, "z": 202.88792820987143, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": -6.64, "front_wheel_angle": -0.33740863777766233, "heading_rate": -0.705759063656823, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059726.2295678}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.64, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059726.2295678}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059726.3303351, "x": -88.23527543896884, "y": 40.09284818927644, "z": 202.88792820987143, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": -6.961, "front_wheel_angle": -0.3557833303877747, "heading_rate": -0.699646287092147, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059726.3297305}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.961, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059726.3297305}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059726.4298887, "x": -88.23527543896884, "y": 40.09284818927644, "z": 202.88792820987143, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": -7.277, "front_wheel_angle": -0.3741109608799742, "heading_rate": -0.7529948119252389, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059726.429757}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059726.429757}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059726.5297465, "x": -88.23527543896884, "y": 40.09284818927644, "z": 202.88792820987143, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": -7.544, "front_wheel_angle": -0.38978869314007175, "heading_rate": -0.7879167643905097, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059726.5296268}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.544, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059726.5296268}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059726.6299424, "x": -88.23524507063208, "y": 40.0928444257169, "z": 202.85229511028112, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": -7.82, "front_wheel_angle": -0.40618670742114166, "heading_rate": -0.7963663711371551, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059726.6295483}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.82, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059726.6295483}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059726.7300227, "x": -88.23524507063208, "y": 40.0928444257169, "z": 202.85229511028112, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": -8.189, "front_wheel_angle": -0.42842724239976887, "heading_rate": -0.904517376608736, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059726.7298703}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.189, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059726.7298703}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059726.8299162, "x": -88.23524507063208, "y": 40.0928444257169, "z": 202.85229511028112, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": -8.494, "front_wheel_angle": -0.4470962418677875, "heading_rate": -0.9027685737206456, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059726.8296947}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.494, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059726.8296947}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059726.9299247, "x": -88.23524507063208, "y": 40.0928444257169, "z": 202.85229511028112, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": -8.784, "front_wheel_angle": -0.4650980569801828, "heading_rate": -0.8820955847045477, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059726.929588}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.784, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059726.929588}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059727.0299547, "x": -88.23524507063208, "y": 40.0928444257169, "z": 202.85229511028112, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": -8.985, "front_wheel_angle": -0.47772427189554556, "heading_rate": -0.9100577295391198, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059727.0297003}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.985, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059727.0297003}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059727.1303678, "x": -88.2352196079505, "y": 40.09283329340795, "z": 202.81565714296917, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": -9.159, "front_wheel_angle": -0.48875625540977696, "heading_rate": -1.036578180036766, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059727.130199}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.159, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059727.130199}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059727.2304943, "x": -88.2352196079505, "y": 40.09283329340795, "z": 202.81565714296917, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": -9.309, "front_wheel_angle": -0.498344440738377, "heading_rate": -1.0436718543262098, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059727.2300253}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.309, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059727.2300253}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059727.329866, "x": -88.2352196079505, "y": 40.09283329340795, "z": 202.81565714296917, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": -9.423, "front_wheel_angle": -0.505680755224573, "heading_rate": -0.9733037491741222, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059727.3295648}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.423, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059727.3295648}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059727.4297843, "x": -88.2352196079505, "y": 40.09283329340795, "z": 202.81565714296917, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9592068162215615, "steering_wheel_angle": -9.59, "front_wheel_angle": -0.5165063977124696, "heading_rate": -0.9606040261739659, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059727.4296696}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.59, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059727.4296696}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059727.530035, "x": -88.2352196079505, "y": 40.09283329340795, "z": 202.81565714296917, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": -9.737, "front_wheel_angle": -0.5261146023633027, "heading_rate": -1.0933672776027568, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059727.5299067}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.737, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059727.5299067}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059727.6297069, "x": -88.23520232749958, "y": 40.0928160581222, "z": 202.77914821046437, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": -9.845, "front_wheel_angle": -0.5332219198538601, "heading_rate": -1.092890717076027, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059727.6295657}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.845, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059727.6295657}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059727.7297833, "x": -88.23520232749958, "y": 40.0928160581222, "z": 202.77914821046437, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": -9.949, "front_wheel_angle": -0.5401053657286667, "heading_rate": -1.091409967199036, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059727.7295966}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.949, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059727.7295966}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059727.830293, "x": -88.23520232749958, "y": 40.0928160581222, "z": 202.77914821046437, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": -10.021, "front_wheel_angle": -0.544893803455702, "heading_rate": -1.0441044905143688, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059727.8295522}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.021, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059727.8295522}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059727.9297895, "x": -88.23520232749958, "y": 40.0928160581222, "z": 202.77914821046437, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9376068162215616, "steering_wheel_angle": -10.104, "front_wheel_angle": -0.5504374671894875, "heading_rate": -0.9996716322762047, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059727.9295526}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.17, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.104, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059727.9295526}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059728.0297892, "x": -88.23520232749958, "y": 40.0928160581222, "z": 202.77914821046437, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": -10.168, "front_wheel_angle": -0.5547296122492894, "heading_rate": -1.1472867288714854, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059728.0295277}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.168, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059728.0295277}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059728.1298947, "x": -88.23519594100179, "y": 40.092795536466646, "z": 202.77355134953984, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9483428162215617, "steering_wheel_angle": -10.203, "front_wheel_angle": -0.5570833948871765, "heading_rate": -1.034101229246929, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059728.1295867}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.25, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.203, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059728.1295867}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059728.2296734, "x": -88.23519594100179, "y": 40.092795536466646, "z": 202.77355134953984, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.986926816221562, "steering_wheel_angle": -10.286, "front_wheel_angle": -0.5626838289847963, "heading_rate": -1.1160337963578264, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059728.2295194}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.53, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.286, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059728.2295194}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059728.3297722, "x": -88.23519594100179, "y": 40.092795536466646, "z": 202.77355134953984, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": -10.429, "front_wheel_angle": -0.5723950848654283, "heading_rate": -1.1099984415525546, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059728.3295422}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.429, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059728.3295422}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059728.4299257, "x": -88.23519594100179, "y": 40.092795536466646, "z": 202.77355134953984, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9456468162215614, "steering_wheel_angle": -10.509, "front_wheel_angle": -0.5778629624609629, "heading_rate": -1.0775237011944752, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059728.4295728}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.509, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059728.4295728}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059728.5297112, "x": -88.23519594100179, "y": 40.092795536466646, "z": 202.77355134953984, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9402788162215616, "steering_wheel_angle": -10.554, "front_wheel_angle": -0.5809498537300624, "heading_rate": -1.0745498361909402, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059728.5295398}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.19, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.554, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059728.5295398}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059728.629694, "x": -88.2352008065235, "y": 40.092775738658965, "z": 202.81412925215037, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9510468162215613, "steering_wheel_angle": -10.556, "front_wheel_angle": -0.581087237622236, "heading_rate": -1.0953942533020073, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059728.6295292}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.27, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.556, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059728.6295292}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059728.730788, "x": -88.2352008065235, "y": 40.092775738658965, "z": 202.81412925215037, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9605738162215616, "steering_wheel_angle": -10.556, "front_wheel_angle": -0.581087237622236, "heading_rate": -1.1133515361430237, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059728.729601}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.556, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059728.729601}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059728.8300357, "x": -88.2352008065235, "y": 40.092775738658965, "z": 202.81412925215037, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9524018162215615, "steering_wheel_angle": -10.556, "front_wheel_angle": -0.581087237622236, "heading_rate": -1.0979595794221526, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059728.8296285}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.556, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059728.8296285}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059728.9297726, "x": -88.2352008065235, "y": 40.092775738658965, "z": 202.81412925215037, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9389418162215613, "steering_wheel_angle": -10.556, "front_wheel_angle": -0.581087237622236, "heading_rate": -1.0723063182207004, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059728.9295568}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.556, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059728.9295568}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059729.0297034, "x": -88.2352008065235, "y": 40.092775738658965, "z": 202.81412925215037, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9256818162215614, "steering_wheel_angle": -10.553, "front_wheel_angle": -0.580881167822624, "heading_rate": -1.0461830523991489, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059729.0295503}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059729.0295503}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059729.1298778, "x": -88.23521481670268, "y": 40.092759643000186, "z": 202.76697699418654, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9178218162215614, "steering_wheel_angle": -10.553, "front_wheel_angle": -0.580881167822624, "heading_rate": -1.030798007510926, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059729.1296265}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059729.1296265}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059729.2298763, "x": -88.23521481670268, "y": 40.092759643000186, "z": 202.76697699418654, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9113268162215618, "steering_wheel_angle": -10.506, "front_wheel_angle": -0.57765745797612, "heading_rate": -1.010838771667163, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059729.2295337}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.506, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059729.2295337}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059729.3298137, "x": -88.23521481670268, "y": 40.092759643000186, "z": 202.76697699418654, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9483428162215617, "steering_wheel_angle": -10.426, "front_wheel_angle": -0.5721905320113926, "heading_rate": -1.0692458684366575, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059729.3295307}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.25, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.426, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059729.3295307}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059729.4302907, "x": -88.23521481670268, "y": 40.092759643000186, "z": 202.76697699418654, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9785268162215615, "steering_wheel_angle": -10.279, "front_wheel_angle": -0.56221048616741, "heading_rate": -1.1000969735664845, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059729.4295871}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.47, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.279, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059729.4295871}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059729.5300322, "x": -88.23521481670268, "y": 40.092759643000186, "z": 202.76697699418654, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8833428162215613, "steering_wheel_angle": -10.112, "front_wheel_angle": -0.5509731471539305, "heading_rate": -0.9000658656555457, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059729.529646}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.75, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.112, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059729.529646}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059729.630168, "x": -88.23523479756726, "y": 40.09274913162666, "z": 202.78847478940435, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9619428162215615, "steering_wheel_angle": -9.951, "front_wheel_angle": -0.5402381225862142, "heading_rate": -1.019112143112912, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059729.6295946}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.35, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.951, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059729.6295946}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059729.730196, "x": -88.23523479756726, "y": 40.09274913162666, "z": 202.78847478940435, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9256818162215614, "steering_wheel_angle": -9.742, "front_wheel_angle": -0.5264427356352103, "heading_rate": -0.9262053623188494, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059729.729614}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.742, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059729.729614}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059729.8297327, "x": -88.23523479756726, "y": 40.09274913162666, "z": 202.78847478940435, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9402788162215616, "steering_wheel_angle": -9.472, "front_wheel_angle": -0.5088473766521192, "heading_rate": -0.9130377138026465, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059729.8295343}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.19, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.472, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059729.8295343}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059729.9296527, "x": -88.23523479756726, "y": 40.09274913162666, "z": 202.78847478940435, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9537588162215616, "steering_wheel_angle": -9.097, "front_wheel_angle": -0.4848143131155275, "heading_rate": -0.8827101164898291, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059729.9295266}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.29, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.097, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059729.9295266}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059730.0298903, "x": -88.23523479756726, "y": 40.09274913162666, "z": 202.78847478940435, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9456468162215614, "steering_wheel_angle": -8.604, "front_wheel_angle": -0.45389515088040144, "heading_rate": -0.8061259713609478, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059730.0295582}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.604, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059730.0295582}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059730.1299324, "x": -88.2352590277632, "y": 40.09274492618194, "z": 202.80981050867737, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.975742816221562, "steering_wheel_angle": -7.917, "front_wheel_angle": -0.41199739717585654, "heading_rate": -0.7596427867337538, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059730.1297202}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.45, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.917, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059730.1297202}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059730.2298818, "x": -88.2352590277632, "y": 40.09274492618194, "z": 202.80981050867737, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9785268162215615, "steering_wheel_angle": -7.104, "front_wheel_angle": -0.3640472050255921, "heading_rate": -0.6653150375507653, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059730.229695}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.47, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.104, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059730.229695}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059730.3298354, "x": -88.2352590277632, "y": 40.09274492618194, "z": 202.80981050867737, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.003942816221562, "steering_wheel_angle": -6.292, "front_wheel_angle": -0.3177541435120047, "heading_rate": -0.597413764451705, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059730.329641}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.292, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059730.329641}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059730.4298685, "x": -88.2352590277632, "y": 40.09274492618194, "z": 202.80981050867737, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.032942816221562, "steering_wheel_angle": -5.4, "front_wheel_angle": -0.2685633184204687, "heading_rate": -0.5213977822419121, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059730.4295828}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.4, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059730.4295828}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059730.5305564, "x": -88.2352590277632, "y": 40.09274492618194, "z": 202.80981050867737, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0314738162215615, "steering_wheel_angle": -4.397, "front_wheel_angle": -0.2151294064302072, "heading_rate": -0.41312197082220975, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059730.5295823}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.84, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.397, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059730.5295823}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059730.6298318, "x": -88.23528673558033, "y": 40.09274613341802, "z": 202.7904596928924, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": -3.668, "front_wheel_angle": -0.17742940867232984, "heading_rate": -0.3551278604350193, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059730.629544}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.668, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059730.629544}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059730.7298384, "x": -88.23528673558033, "y": 40.09274613341802, "z": 202.7904596928924, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": -3.06, "front_wheel_angle": -0.14666345347498183, "heading_rate": -0.301795854873138, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059730.7295363}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.06, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059730.7295363}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059730.8297775, "x": -88.23528673558033, "y": 40.09274613341802, "z": 202.7904596928924, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": -2.371, "front_wheel_angle": -0.1124960117201629, "heading_rate": -0.23830239081083082, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059730.829555}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.371, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059730.829555}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059730.9302588, "x": -88.23528673558033, "y": 40.09274613341802, "z": 202.7904596928924, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": -1.649, "front_wheel_angle": -0.07743953174717741, "heading_rate": -0.17095082900762942, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059730.9297106}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.649, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059730.9297106}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059731.029864, "x": -88.23528673558033, "y": 40.09274613341802, "z": 202.7904596928924, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.183278816221561, "steering_wheel_angle": -1.315, "front_wheel_angle": -0.06146804260021665, "heading_rate": -0.1396796059802469, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059731.0295906}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.315, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059731.0295906}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059731.129924, "x": -88.235318126849, "y": 40.0927508506569, "z": 202.81326123272308, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1966388162215615, "steering_wheel_angle": -1.484, "front_wheel_angle": -0.06953048650567983, "heading_rate": -0.16023273736120222, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059731.1295824}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.484, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059731.1295824}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059731.2306802, "x": -88.235318126849, "y": 40.0927508506569, "z": 202.81326123272308, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.237486816221562, "steering_wheel_angle": -1.873, "front_wheel_angle": -0.08823679015121737, "heading_rate": -0.21183580251812173, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059731.229646}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.873, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059731.229646}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059731.3298023, "x": -88.235318126849, "y": 40.0927508506569, "z": 202.81326123272308, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.2531018162215615, "steering_wheel_angle": -2.265, "front_wheel_angle": -0.1073024440258679, "heading_rate": -0.2617166310673412, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059731.3295774}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.265, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059731.3295774}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059731.4297915, "x": -88.235318126849, "y": 40.0927508506569, "z": 202.81326123272308, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.267117816221561, "steering_wheel_angle": -2.378, "front_wheel_angle": -0.11283956204827253, "heading_rate": -0.2788757355641181, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059731.429575}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.378, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059731.429575}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059731.5297012, "x": -88.235318126849, "y": 40.0927508506569, "z": 202.81326123272308, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": -2.104, "front_wheel_angle": -0.09944530464659641, "heading_rate": -0.2517745223343258, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059731.5295591}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.104, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059731.5295591}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059731.6298988, "x": -88.23535359527801, "y": 40.09275844431116, "z": 202.81943676182942, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.324461816221562, "steering_wheel_angle": -1.506, "front_wheel_angle": -0.07058287763787637, "heading_rate": -0.1828266216067489, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059731.629589}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.506, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059731.629589}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059731.7297797, "x": -88.23535359527801, "y": 40.09275844431116, "z": 202.81943676182942, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.355758816221561, "steering_wheel_angle": -0.772, "front_wheel_angle": -0.03581946021021088, "heading_rate": -0.0950461740433605, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059731.7295465}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.772, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059731.7295465}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059731.8297546, "x": -88.23535359527801, "y": 40.09275844431116, "z": 202.81943676182942, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.355758816221561, "steering_wheel_angle": -0.143, "front_wheel_angle": -0.006579511737334867, "heading_rate": -0.01745137865854542, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059731.8295379}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.143, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059731.8295379}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059731.929882, "x": -88.23535359527801, "y": 40.09275844431116, "z": 202.81943676182942, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": 0.38, "front_wheel_angle": 0.017538946139153216, "heading_rate": 0.04707223304214847, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059731.9296184}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.38, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059731.9296184}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059732.0301206, "x": -88.23535359527801, "y": 40.09275844431116, "z": 202.81943676182942, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": 0.773, "front_wheel_angle": 0.035866343042575015, "heading_rate": 0.09979606262826915, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059732.029614}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.773, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059732.029614}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059732.129787, "x": -88.23535359527801, "y": 40.09275844431116, "z": 202.81943676182942, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": 0.718, "front_wheel_angle": 0.03328968529822271, "heading_rate": 0.09262115411520981, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059732.129559}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.718, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059732.129559}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059732.2296734, "x": -88.23539169105638, "y": 40.092768370894746, "z": 202.811933201706, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": 0.309, "front_wheel_angle": 0.01424849260421881, "heading_rate": 0.04007659759689645, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059732.2295265}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.309, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059732.2295265}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059732.329865, "x": -88.23539169105638, "y": 40.092768370894746, "z": 202.811933201706, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.464913816221562, "steering_wheel_angle": -0.164, "front_wheel_angle": -0.007547822295530698, "heading_rate": -0.021700401189095893, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059732.3295946}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.164, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059732.3295946}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059732.4301934, "x": -88.23539169105638, "y": 40.092768370894746, "z": 202.811933201706, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.480753816221561, "steering_wheel_angle": -0.638, "front_wheel_angle": -0.02954869630938124, "heading_rate": -0.08590090085885514, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059732.4295669}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059732.4295669}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059732.5298085, "x": -88.23539169105638, "y": 40.092768370894746, "z": 202.811933201706, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.496721816221561, "steering_wheel_angle": -0.977, "front_wheel_angle": -0.045457356970548576, "heading_rate": -0.13362303705221498, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059732.529534}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.977, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059732.529534}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059732.6304193, "x": -88.23543270896226, "y": 40.09277803222142, "z": 202.78492634160935, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.514838816221562, "steering_wheel_angle": -0.857, "front_wheel_angle": -0.03980908127619132, "heading_rate": -0.11840126685185685, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059732.6295738}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.857, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059732.6295738}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059732.7299988, "x": -88.23543270896226, "y": 40.09277803222142, "z": 202.78492634160935, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.531078816221561, "steering_wheel_angle": -0.383, "front_wheel_angle": -0.01767811677342035, "heading_rate": -0.053108938040153035, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059732.7295432}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.383, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059732.7295432}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059732.8299646, "x": -88.23543270896226, "y": 40.09277803222142, "z": 202.78492634160935, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.547446816221561, "steering_wheel_angle": 0.166, "front_wheel_angle": 0.007640070366829615, "heading_rate": 0.02318925851697088, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059732.8295634}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059732.8295634}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059732.9298027, "x": -88.23543270896226, "y": 40.09277803222142, "z": 202.78492634160935, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.563942816221561, "steering_wheel_angle": 0.783, "front_wheel_angle": 0.03633524178859028, "heading_rate": 0.1114676718910181, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059732.9295764}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.783, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059732.9295764}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059733.029692, "x": -88.23543270896226, "y": 40.09277803222142, "z": 202.78492634160935, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": 1.337, "front_wheel_angle": 0.06251541447825139, "heading_rate": 0.1961046090171463, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059733.029526}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.337, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059733.029526}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059733.1297414, "x": -88.23547565587714, "y": 40.092788833882786, "z": 202.84449443555815, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": 1.31, "front_wheel_angle": 0.06123009396957922, "heading_rate": 0.19397832109823834, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059733.1295455}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.31, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059733.1295455}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059733.2298412, "x": -88.23547565587714, "y": 40.092788833882786, "z": 202.84449443555815, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": 0.88, "front_wheel_angle": 0.040890223962770846, "heading_rate": 0.12945138031937606, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059733.2295406}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.88, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059733.2295406}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059733.3299482, "x": -88.23547565587714, "y": 40.092788833882786, "z": 202.84449443555815, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.633341816221561, "steering_wheel_angle": 0.308, "front_wheel_angle": 0.014202192656884017, "heading_rate": 0.0453834950830687, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059733.329561}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.308, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059733.329561}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059733.4302588, "x": -88.23547565587714, "y": 40.092788833882786, "z": 202.84449443555815, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.650493816221561, "steering_wheel_angle": -0.25, "front_wheel_angle": -0.011518901902098604, "heading_rate": -0.03716810081743549, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059733.4296422}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.26, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.25, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059733.4296422}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059733.5297785, "x": -88.23547565587714, "y": 40.092788833882786, "z": 202.84449443555815, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.667773816221562, "steering_wheel_angle": -0.763, "front_wheel_angle": -0.03539757230578276, "heading_rate": -0.11536684198055996, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059733.5295837}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.763, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059733.5295837}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059733.6299999, "x": -88.23552113204497, "y": 40.09279853695827, "z": 202.83028278022636, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.667773816221562, "steering_wheel_angle": -1.043, "front_wheel_angle": -0.04857188712145214, "heading_rate": -0.15836265848903405, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059733.6295576}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.043, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059733.6295576}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059733.729742, "x": -88.23552113204497, "y": 40.09279853695827, "z": 202.83028278022636, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.704918816221562, "steering_wheel_angle": -0.84, "front_wheel_angle": -0.039010414127701044, "heading_rate": -0.129744972603326, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059733.729566}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.51, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.84, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059733.729566}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059733.8297958, "x": -88.23552113204497, "y": 40.09279853695827, "z": 202.83028278022636, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.704918816221562, "steering_wheel_angle": -0.401, "front_wheel_angle": -0.0185133750824784, "heading_rate": -0.0615495406692473, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059733.8295457}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.51, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.401, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059733.8295457}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059733.9298697, "x": -88.23552113204497, "y": 40.09279853695827, "z": 202.83028278022636, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.722598816221561, "steering_wheel_angle": 0.092, "front_wheel_angle": 0.004230132597423936, "heading_rate": 0.014194162402663794, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059733.9295535}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.59, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059733.9295535}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059734.0298069, "x": -88.23552113204497, "y": 40.09279853695827, "z": 202.83028278022636, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.722598816221561, "steering_wheel_angle": 0.689, "front_wheel_angle": 0.031932637198262906, "heading_rate": 0.10718540077973876, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059734.0295432}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.59, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.689, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059734.0295432}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059734.1308618, "x": -88.23556830983189, "y": 40.092809051528114, "z": 202.84495612135183, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.740406816221562, "steering_wheel_angle": 1.307, "front_wheel_angle": 0.06108734085452712, "heading_rate": 0.20714336988096282, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059734.1297336}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059734.1297336}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059734.230269, "x": -88.23556830983189, "y": 40.092809051528114, "z": 202.84495612135183, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.758342816221561, "steering_wheel_angle": 1.426, "front_wheel_angle": 0.06675914914244975, "heading_rate": 0.22852027495803995, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059734.229559}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.75, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.426, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059734.229559}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059734.3298366, "x": -88.23556830983189, "y": 40.092809051528114, "z": 202.84495612135183, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.758342816221561, "steering_wheel_angle": 1.02, "front_wheel_angle": 0.04748587487854268, "heading_rate": 0.16242734101193276, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059734.329562}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.75, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.02, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059734.329562}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059734.4297364, "x": -88.23556830983189, "y": 40.092809051528114, "z": 202.84495612135183, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.758342816221561, "steering_wheel_angle": 0.42, "front_wheel_angle": 0.019395473224732146, "heading_rate": 0.06630143543693642, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059734.429564}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.75, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.42, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059734.429564}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059734.5297632, "x": -88.23556830983189, "y": 40.092809051528114, "z": 202.84495612135183, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.776406816221561, "steering_wheel_angle": -0.119, "front_wheel_angle": -0.005473528100865687, "heading_rate": -0.01887958429556508, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059734.5295296}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.119, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059734.5295296}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059734.6297317, "x": -88.23561706956777, "y": 40.092818967358944, "z": 202.87995480856614, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.796881816221561, "steering_wheel_angle": -0.589, "front_wheel_angle": -0.027261345335914174, "heading_rate": -0.09501228842864078, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059734.629545}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.589, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059734.629545}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059734.72987, "x": -88.23561706956777, "y": 40.092818967358944, "z": 202.87995480856614, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.815217816221562, "steering_wheel_angle": -0.897, "front_wheel_angle": -0.04168976842853566, "heading_rate": -0.14665056333579496, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059734.7295814}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.897, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059734.7295814}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059734.830233, "x": -88.23561706956777, "y": 40.092818967358944, "z": 202.87995480856614, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.776406816221561, "steering_wheel_angle": -0.735, "front_wheel_angle": -0.03408569436046921, "heading_rate": -0.11761456918043924, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059734.8296607}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.735, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059734.8296607}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059734.9297268, "x": -88.23561706956777, "y": 40.092818967358944, "z": 202.87995480856614, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.852273816221562, "steering_wheel_angle": -0.282, "front_wheel_angle": -0.012998826464549688, "heading_rate": -0.046514045791168565, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059734.9295318}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.282, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059734.9295318}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059735.0298645, "x": -88.23561706956777, "y": 40.092818967358944, "z": 202.87995480856614, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.776406816221561, "steering_wheel_angle": 0.234, "front_wheel_angle": 0.010779411046211277, "heading_rate": 0.037181986834731874, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059735.0295408}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.234, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059735.0295408}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059735.1302147, "x": -88.23566774779734, "y": 40.092828887170434, "z": 202.93615671903189, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.852273816221562, "steering_wheel_angle": 0.698, "front_wheel_angle": 0.03235367551845623, "heading_rate": 0.11580590504324396, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059735.1295767}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.698, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059735.1295767}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059735.2297328, "x": -88.23566774779734, "y": 40.092828887170434, "z": 202.93615671903189, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.796881816221561, "steering_wheel_angle": 0.855, "front_wheel_angle": 0.03971510111100398, "heading_rate": 0.13845510767394828, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059735.229536}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.855, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059735.229536}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059735.3297398, "x": -88.23566774779734, "y": 40.092828887170434, "z": 202.93615671903189, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.833681816221562, "steering_wheel_angle": 0.69, "front_wheel_angle": 0.03197941414711899, "heading_rate": 0.11346566699069126, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059735.3295588}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.69, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059735.3295588}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059735.4296918, "x": -88.23566774779734, "y": 40.092828887170434, "z": 202.93615671903189, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.815217816221562, "steering_wheel_angle": 0.608, "front_wheel_angle": 0.028147917288204136, "heading_rate": 0.09898366485629659, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059735.4295557}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.608, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059735.4295557}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059735.5297582, "x": -88.23566774779734, "y": 40.092828887170434, "z": 202.93615671903189, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.796881816221561, "steering_wheel_angle": 0.696, "front_wheel_angle": 0.03226010254408828, "heading_rate": 0.11244530531798609, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059735.5295446}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.696, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059735.5295446}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059735.629884, "x": -88.23571849711897, "y": 40.09283871381105, "z": 203.0114048719602, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.776406816221561, "steering_wheel_angle": 0.823, "front_wheel_angle": 0.0382121189655388, "heading_rate": 0.13186614561751206, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059735.6295795}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.823, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059735.6295795}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059735.7298012, "x": -88.23571849711897, "y": 40.09283871381105, "z": 203.0114048719602, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.758342816221561, "steering_wheel_angle": 0.942, "front_wheel_angle": 0.043808015073501516, "heading_rate": 0.1498302873277821, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059735.729569}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.75, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.942, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059735.729569}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059735.8299286, "x": -88.23571849711897, "y": 40.09283871381105, "z": 203.0114048719602, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.833681816221562, "steering_wheel_angle": 1.02, "front_wheel_angle": 0.04748587487854268, "heading_rate": 0.16855317215866852, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059735.8295336}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.02, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059735.8295336}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059735.9297986, "x": -88.23571849711897, "y": 40.09283871381105, "z": 203.0114048719602, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.815217816221562, "steering_wheel_angle": 1.077, "front_wheel_angle": 0.050178565268322116, "heading_rate": 0.17655722720025943, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059735.9295382}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.077, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059735.9295382}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059736.0297663, "x": -88.23571849711897, "y": 40.09283871381105, "z": 203.0114048719602, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.776406816221561, "steering_wheel_angle": 1.11, "front_wheel_angle": 0.05173943926274652, "heading_rate": 0.1786200592931343, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059736.0295825}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.11, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059736.0295825}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059736.129781, "x": -88.23576942343067, "y": 40.092843908049666, "z": 203.0516681710137, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.758342816221561, "steering_wheel_angle": 1.101, "front_wheel_angle": 0.051313604365133283, "heading_rate": 0.17554239596378488, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059736.1295614}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.75, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.101, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059736.1295614}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059736.2297938, "x": -88.23576942343067, "y": 40.092843908049666, "z": 203.0516681710137, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.740406816221562, "steering_wheel_angle": 1.03, "front_wheel_angle": 0.047957969118711245, "heading_rate": 0.162544788210178, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059736.2295496}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.03, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059736.2295496}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059736.3297908, "x": -88.23576942343067, "y": 40.092843908049666, "z": 203.0516681710137, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.722598816221561, "steering_wheel_angle": 0.984, "front_wheel_angle": 0.0457874165644552, "heading_rate": 0.1537457024268864, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059736.3295143}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.59, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.984, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059736.3295143}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059736.430065, "x": -88.23576942343067, "y": 40.092843908049666, "z": 203.0516681710137, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.776406816221561, "steering_wheel_angle": 0.994, "front_wheel_angle": 0.046259040995053576, "heading_rate": 0.15967146140199742, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059736.4295332}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.994, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059736.4295332}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059736.530124, "x": -88.23576942343067, "y": 40.092843908049666, "z": 203.0516681710137, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.758342816221561, "steering_wheel_angle": 0.99, "front_wheel_angle": 0.04607037558543262, "heading_rate": 0.1575786056170804, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059736.529641}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.75, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.99, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059736.529641}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059736.629898, "x": -88.2358193901445, "y": 40.09284666703118, "z": 203.09023540030321, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.722598816221561, "steering_wheel_angle": 0.939, "front_wheel_angle": 0.04366671696330783, "heading_rate": 0.14661550397652642, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059736.629568}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.59, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.939, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059736.629568}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059736.7301528, "x": -88.2358193901445, "y": 40.09284666703118, "z": 203.09023540030321, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.704918816221562, "steering_wheel_angle": 0.843, "front_wheel_angle": 0.03915132834423476, "heading_rate": 0.13021411845338912, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059736.7296145}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.51, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.843, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059736.7296145}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059736.8299212, "x": -88.2358193901445, "y": 40.09284666703118, "z": 203.09023540030321, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.687366816221561, "steering_wheel_angle": 0.703, "front_wheel_angle": 0.03258763022088541, "heading_rate": 0.10734805019546026, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059736.8295355}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.703, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059736.8295355}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059736.9298475, "x": -88.2358193901445, "y": 40.09284666703118, "z": 203.09023540030321, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.704918816221562, "steering_wheel_angle": 0.505, "front_wheel_angle": 0.023347209769393328, "heading_rate": 0.07762533731023812, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059736.9295375}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.51, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.505, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059736.9295375}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059737.0297244, "x": -88.2358193901445, "y": 40.09284666703118, "z": 203.09023540030321, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.687366816221561, "steering_wheel_angle": 0.285, "front_wheel_angle": 0.013137633932330927, "heading_rate": 0.04326430711941932, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059737.029553}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.285, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059737.029553}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059737.1297631, "x": -88.23586869828189, "y": 40.09284590851971, "z": 203.09285932665117, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.650493816221561, "steering_wheel_angle": 0.061, "front_wheel_angle": 0.002803619707913495, "heading_rate": 0.009046077915405949, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059737.1295683}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.26, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.061, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059737.1295683}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059737.229729, "x": -88.23586869828189, "y": 40.09284590851971, "z": 203.09285932665117, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.667773816221562, "steering_wheel_angle": 0.061, "front_wheel_angle": 0.002803619707913495, "heading_rate": 0.00913369126083361, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059737.229537}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.061, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059737.229537}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059737.329891, "x": -88.23586869828189, "y": 40.09284590851971, "z": 203.09285932665117, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.633341816221561, "steering_wheel_angle": -0.15, "front_wheel_angle": -0.006902222257807445, "heading_rate": -0.022055107299307698, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059737.3295813}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.15, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059737.3295813}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059737.4297671, "x": -88.23586869828189, "y": 40.09284590851971, "z": 203.09285932665117, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": -0.281, "front_wheel_angle": -0.0129525597693176, "heading_rate": -0.040985000672264765, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059737.429571}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.281, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059737.429571}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059737.529964, "x": -88.23586869828189, "y": 40.09284590851971, "z": 203.09285932665117, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": -0.344, "front_wheel_angle": -0.015869768215077257, "heading_rate": -0.04972118239207211, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059737.529523}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.344, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059737.529523}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059737.630079, "x": -88.23591663985626, "y": 40.092844693525976, "z": 203.09488010349554, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.563942816221561, "steering_wheel_angle": -0.392, "front_wheel_angle": -0.018095695661081455, "heading_rate": -0.055494811741896875, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059737.6295893}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.392, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059737.6295893}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059737.7297444, "x": -88.23591663985626, "y": 40.092844693525976, "z": 203.09488010349554, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.547446816221561, "steering_wheel_angle": -0.473, "front_wheel_angle": -0.021858438404162916, "heading_rate": -0.06635434411769602, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059737.7295492}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.473, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059737.7295492}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059737.829773, "x": -88.23591663985626, "y": 40.092844693525976, "z": 203.09488010349554, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.514838816221562, "steering_wheel_angle": -0.484, "front_wheel_angle": -0.022370059103631008, "heading_rate": -0.06650959061042211, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059737.829538}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.484, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059737.829538}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059737.929728, "x": -88.23591663985626, "y": 40.092844693525976, "z": 203.09488010349554, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.514838816221562, "steering_wheel_angle": -0.405, "front_wheel_angle": -0.018699042669962463, "heading_rate": -0.05559230557390542, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059737.9295292}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.405, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059737.9295292}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059738.0299592, "x": -88.23591663985626, "y": 40.092844693525976, "z": 203.09488010349554, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.480753816221561, "steering_wheel_angle": -0.311, "front_wheel_angle": -0.014341096197796534, "heading_rate": -0.041681668379148135, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059738.0296204}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.311, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059738.0296204}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059738.1297712, "x": -88.23596190482202, "y": 40.09284495173245, "z": 203.08550895606768, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.449201816221562, "steering_wheel_angle": -0.216, "front_wheel_angle": -0.009947858842904795, "heading_rate": -0.028290156787654192, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059738.129565}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.216, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059738.129565}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059738.2298658, "x": -88.23596190482202, "y": 40.09284495173245, "z": 203.08550895606768, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": -0.031, "front_wheel_angle": -0.0014242295429861569, "heading_rate": -0.004005648298041046, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059738.229598}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.031, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059738.229598}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059738.329753, "x": -88.23596190482202, "y": 40.09284495173245, "z": 203.08550895606768, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": 0.218, "front_wheel_angle": 0.010040233940451006, "heading_rate": 0.02792533900319671, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059738.3295527}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.218, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059738.3295527}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059738.4299614, "x": -88.23596190482202, "y": 40.09284495173245, "z": 203.08550895606768, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.400926816221562, "steering_wheel_angle": 0.431, "front_wheel_angle": 0.019906366830852815, "heading_rate": 0.05467197123133182, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059738.429595}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.431, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059738.429595}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059738.5296984, "x": -88.23596190482202, "y": 40.09284495173245, "z": 203.08550895606768, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": 0.571, "front_wheel_angle": 0.026421855002635993, "heading_rate": 0.0709220296138703, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059738.5295346}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.571, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059738.5295346}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059738.6298175, "x": -88.23600308118785, "y": 40.09284518364068, "z": 203.07848876708655, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.340958816221562, "steering_wheel_angle": 0.822, "front_wheel_angle": 0.03816517199983321, "heading_rate": 0.10008309153736138, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059738.6295416}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.822, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059738.6295416}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059738.7298594, "x": -88.23600308118785, "y": 40.09284518364068, "z": 203.07848876708655, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3099338162215615, "steering_wheel_angle": 1.238, "front_wheel_angle": 0.05780733713387394, "heading_rate": 0.14784440158259765, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059738.7295709}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.54, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.238, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059738.7295709}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059738.8299253, "x": -88.23600308118785, "y": 40.09284518364068, "z": 203.07848876708655, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": 1.749, "front_wheel_angle": 0.08225111418324844, "heading_rate": 0.20544871139706722, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059738.8295505}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.749, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059738.8295505}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059738.9297028, "x": -88.23600308118785, "y": 40.09284518364068, "z": 203.07848876708655, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.2531018162215615, "steering_wheel_angle": 2.233, "front_wheel_angle": 0.1057377923536396, "heading_rate": 0.25787155209056456, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059738.929524}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.233, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059738.929524}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059739.0303524, "x": -88.23600308118785, "y": 40.09284518364068, "z": 203.07848876708655, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.237486816221562, "steering_wheel_angle": 2.634, "front_wheel_angle": 0.12545350979025102, "heading_rate": 0.3019883037482732, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059739.029684}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.634, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059739.029684}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059739.129914, "x": -88.23603941928654, "y": 40.092843236840885, "z": 203.0691389001837, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.210126816221561, "steering_wheel_angle": 2.971, "front_wheel_angle": 0.1422091889038195, "heading_rate": 0.33389011675908187, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059739.1295507}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.971, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059739.1295507}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059739.2299235, "x": -88.23603941928654, "y": 40.092843236840885, "z": 203.0691389001837, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.183278816221561, "steering_wheel_angle": 3.291, "front_wheel_angle": 0.15828257437538518, "heading_rate": 0.36225757188920504, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059739.2295852}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.291, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059739.2295852}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059739.3298573, "x": -88.23603941928654, "y": 40.092843236840885, "z": 203.0691389001837, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.183278816221561, "steering_wheel_angle": 3.562, "front_wheel_angle": 0.1720225149655828, "heading_rate": 0.3943075846668146, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059739.3295524}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.562, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059739.3295524}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059739.4297452, "x": -88.23603941928654, "y": 40.092843236840885, "z": 203.0691389001837, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.142353816221561, "steering_wheel_angle": 3.804, "front_wheel_angle": 0.18439385117913512, "heading_rate": 0.4050819119496226, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059739.429577}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.804, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059739.429577}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059739.5298636, "x": -88.23603941928654, "y": 40.092843236840885, "z": 203.0691389001837, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": 4.07, "front_wheel_angle": 0.19810565208827025, "heading_rate": 0.4297060676522294, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059739.5295506}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.07, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059739.5295506}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059739.6298, "x": -88.23607019760378, "y": 40.09283705229139, "z": 203.08737144405978, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": 4.423, "front_wheel_angle": 0.21649107186234445, "heading_rate": 0.4561993177013623, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059739.629591}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.423, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059739.629591}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059739.7297883, "x": -88.23607019760378, "y": 40.09283705229139, "z": 203.08737144405978, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": 4.801, "front_wheel_angle": 0.23642568178584147, "heading_rate": 0.4846866707062158, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059739.7295396}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.801, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059739.7295396}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059739.829833, "x": -88.23607019760378, "y": 40.09283705229139, "z": 203.08737144405978, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": 5.172, "front_wheel_angle": 0.25624928535299235, "heading_rate": 0.5189013950978751, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059739.829543}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.172, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059739.829543}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059739.9297488, "x": -88.23607019760378, "y": 40.09283705229139, "z": 203.08737144405978, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": 5.483, "front_wheel_angle": 0.27307149762371585, "heading_rate": 0.5371611325795105, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059739.929556}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.483, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059739.929556}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059740.0297503, "x": -88.23607019760378, "y": 40.09283705229139, "z": 203.08737144405978, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": 5.741, "front_wheel_angle": 0.28717340615260706, "heading_rate": 0.5560643273911302, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059740.0295317}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.741, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059740.0295317}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059740.1297336, "x": -88.23609413635013, "y": 40.09282636775101, "z": 203.1055588032695, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": 5.923, "front_wheel_angle": 0.29720343240956987, "heading_rate": 0.5575157048617517, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059740.1295562}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.923, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059740.1295562}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059740.2298145, "x": -88.23609413635013, "y": 40.09282636775101, "z": 203.1055588032695, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": 6.173, "front_wheel_angle": 0.31109467967158855, "heading_rate": 0.585294058432849, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059740.2295892}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.173, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059740.2295892}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059740.32985, "x": -88.23609413635013, "y": 40.09282636775101, "z": 203.1055588032695, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": 6.408, "front_wheel_angle": 0.32427559853196763, "heading_rate": 0.5908733917651617, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059740.329545}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059740.329545}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059740.4298515, "x": -88.23609413635013, "y": 40.09282636775101, "z": 203.1055588032695, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9592068162215615, "steering_wheel_angle": 6.567, "front_wheel_angle": 0.3332631598231364, "heading_rate": 0.585522498888547, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059740.4295547}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.567, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059740.4295547}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059740.5297341, "x": -88.23609413635013, "y": 40.09282636775101, "z": 203.1055588032695, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9592068162215615, "steering_wheel_angle": 6.714, "front_wheel_angle": 0.34162333062929473, "heading_rate": 0.6014038259251946, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059740.5295286}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.714, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059740.5295286}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059740.6297345, "x": -88.23611038569507, "y": 40.09281283340683, "z": 203.08756949456225, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": 6.892, "front_wheel_angle": 0.3518132988625218, "heading_rate": 0.6323608758513662, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059740.6295648}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.892, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059740.6295648}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059740.7299297, "x": -88.23611038569507, "y": 40.09281283340683, "z": 203.08756949456225, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9592068162215615, "steering_wheel_angle": 7.133, "front_wheel_angle": 0.36572909963208533, "heading_rate": 0.647737304760546, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059740.7295964}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.133, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059740.7295964}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059740.8298266, "x": -88.23611038569507, "y": 40.09281283340683, "z": 203.08756949456225, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9376068162215616, "steering_wheel_angle": 7.407, "front_wheel_angle": 0.381721923199408, "heading_rate": 0.6538604307453446, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059740.8295767}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.17, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.407, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059740.8295767}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059740.9297283, "x": -88.23611038569507, "y": 40.09281283340683, "z": 203.08756949456225, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9269988162215617, "steering_wheel_angle": 7.675, "front_wheel_angle": 0.3975470742638534, "heading_rate": 0.670863547571893, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059740.9295528}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.09, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.675, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059740.9295528}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059741.0298033, "x": -88.23611038569507, "y": 40.09281283340683, "z": 203.08756949456225, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9139188162215617, "steering_wheel_angle": 7.863, "front_wheel_angle": 0.40875948081754626, "heading_rate": 0.6751160112377746, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059741.0295353}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.863, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059741.0295353}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059741.1298296, "x": -88.23611991952549, "y": 40.09279781956222, "z": 203.06941700254723, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9100338162215618, "steering_wheel_angle": 7.999, "front_wheel_angle": 0.4169292383356491, "heading_rate": 0.6851023121674287, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059741.1295972}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.96, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.999, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059741.1295972}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059741.229837, "x": -88.23611991952549, "y": 40.09279781956222, "z": 203.06941700254723, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.932286816221562, "steering_wheel_angle": 8.154, "front_wheel_angle": 0.42630170139607804, "heading_rate": 0.7326755655411318, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059741.2295444}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.154, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059741.2295444}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059741.3298297, "x": -88.23611991952549, "y": 40.09279781956222, "z": 203.06941700254723, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9204338162215615, "steering_wheel_angle": 8.313, "front_wheel_angle": 0.43598533656472094, "heading_rate": 0.7352252430108975, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059741.3295343}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.04, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.313, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059741.3295343}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059741.4297898, "x": -88.23611991952549, "y": 40.09279781956222, "z": 203.06941700254723, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9023178162215615, "steering_wheel_angle": 8.459, "front_wheel_angle": 0.4449403636559511, "heading_rate": 0.7264206485228358, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059741.4295585}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.9, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.459, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059741.4295585}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059741.530042, "x": -88.23611991952549, "y": 40.09279781956222, "z": 203.06941700254723, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.919126816221562, "steering_wheel_angle": 8.56, "front_wheel_angle": 0.45117132624912765, "heading_rate": 0.7627098190763695, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059741.5295677}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.56, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059741.5295677}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059741.6298308, "x": -88.23612369312829, "y": 40.09278235599735, "z": 203.1067525797775, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9074538162215617, "steering_wheel_angle": 8.617, "front_wheel_angle": 0.4547010108874807, "heading_rate": 0.7523957280532666, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059741.629541}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.94, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.617, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059741.629541}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059741.729734, "x": -88.23612369312829, "y": 40.09278235599735, "z": 203.1067525797775, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8921418162215615, "steering_wheel_angle": 8.646, "front_wheel_angle": 0.4565005036271267, "heading_rate": 0.7328099674877088, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059741.7295232}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.646, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059741.7295232}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059741.8296854, "x": -88.23612369312829, "y": 40.09278235599735, "z": 203.1067525797775, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8921418162215615, "steering_wheel_angle": 8.732, "front_wheel_angle": 0.46185167723272685, "heading_rate": 0.7427469180736546, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059741.8295248}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.732, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059741.8295248}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059741.929693, "x": -88.23612369312829, "y": 40.09278235599735, "z": 203.1067525797775, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8959428162215617, "steering_wheel_angle": 8.91, "front_wheel_angle": 0.47299843115447854, "heading_rate": 0.769614664572682, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059741.9295232}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.91, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059741.9295232}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059742.0296993, "x": -88.23612369312829, "y": 40.09278235599735, "z": 203.1067525797775, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8908788162215617, "steering_wheel_angle": 9.134, "front_wheel_angle": 0.4871652855509566, "heading_rate": 0.7884206163501642, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059742.029528}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.134, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059742.029528}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059742.1297076, "x": -88.23612172887228, "y": 40.09276772094823, "z": 203.05878548012106, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8808468162215615, "steering_wheel_angle": 9.355, "front_wheel_angle": 0.501299533213756, "heading_rate": 0.79844010469798, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059742.129524}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.73, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.355, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059742.129524}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059742.2297404, "x": -88.23612172887228, "y": 40.09276772094823, "z": 203.05878548012106, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8758788162215616, "steering_wheel_angle": 9.487, "front_wheel_angle": 0.5098183631133261, "heading_rate": 0.805919454616991, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059742.2295353}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.487, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059742.2295353}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059742.3298163, "x": -88.23612172887228, "y": 40.09276772094823, "z": 203.05878548012106, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8758788162215616, "steering_wheel_angle": 9.56, "front_wheel_angle": 0.5145546985332841, "heading_rate": 0.8149045200683073, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059742.3295395}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.56, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059742.3295395}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059742.4296906, "x": -88.23612172887228, "y": 40.09276772094823, "z": 203.05878548012106, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8660388162215615, "steering_wheel_angle": 9.6, "front_wheel_angle": 0.5171576490542907, "heading_rate": 0.8020881345776354, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059742.4295275}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.6, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059742.4295275}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059742.5297296, "x": -88.23612172887228, "y": 40.09276772094823, "z": 203.05878548012106, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8684868162215613, "steering_wheel_angle": 9.644, "front_wheel_angle": 0.5200272416093256, "heading_rate": 0.8119260745119771, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059742.5295312}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.63, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.644, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059742.5295312}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059742.629707, "x": -88.23611374761299, "y": 40.092755545118976, "z": 203.0082513333114, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8611668162215613, "steering_wheel_angle": 9.743, "front_wheel_angle": 0.5265083728243672, "heading_rate": 0.8105521436128738, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059742.6295269}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.743, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059742.6295269}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059742.7297802, "x": -88.23611374761299, "y": 40.092755545118976, "z": 203.0082513333114, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8684868162215613, "steering_wheel_angle": 9.822, "front_wheel_angle": 0.5317048581411601, "heading_rate": 0.8340626023028408, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059742.7295191}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.63, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.822, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059742.7295191}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059742.829974, "x": -88.23611374761299, "y": 40.092755545118976, "z": 203.0082513333114, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8551218162215615, "steering_wheel_angle": 9.893, "front_wheel_angle": 0.5363940553396983, "heading_rate": 0.8174905148288587, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059742.8295329}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.893, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059742.8295329}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059742.929809, "x": -88.23611374761299, "y": 40.092755545118976, "z": 203.0082513333114, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8503218162215616, "steering_wheel_angle": 9.937, "front_wheel_angle": 0.5393091295366285, "heading_rate": 0.8135735679725649, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059742.92953}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.937, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059742.92953}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059743.0296888, "x": -88.23611374761299, "y": 40.092755545118976, "z": 203.0082513333114, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.843181816221562, "steering_wheel_angle": 9.987, "front_wheel_angle": 0.5426302360242441, "heading_rate": 0.8055844719850587, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059743.029522}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.42, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.987, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059743.029522}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059743.1298103, "x": -88.23610110812464, "y": 40.09274701977745, "z": 203.01785550443304, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8455538162215617, "steering_wheel_angle": 9.99, "front_wheel_angle": 0.5428297922508948, "heading_rate": 0.8106611964992412, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059743.1295447}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.99, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059743.1295447}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059743.2298653, "x": -88.23610110812464, "y": 40.09274701977745, "z": 203.01785550443304, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8491268162215615, "steering_wheel_angle": 9.99, "front_wheel_angle": 0.5428297922508948, "heading_rate": 0.8177309162361532, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059743.2295344}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.47, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.99, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059743.2295344}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059743.3297, "x": -88.23610110812464, "y": 40.09274701977745, "z": 203.01785550443304, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.840817816221562, "steering_wheel_angle": 9.987, "front_wheel_angle": 0.5426302360242441, "heading_rate": 0.8008734516810523, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059743.3295305}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.987, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059743.3295305}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059743.4296715, "x": -88.23610110812464, "y": 40.09274701977745, "z": 203.01785550443304, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8384618162215616, "steering_wheel_angle": 9.987, "front_wheel_angle": 0.5426302360242441, "heading_rate": 0.7961624313770461, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059743.4295142}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.987, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059743.4295142}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059743.5298038, "x": -88.23610110812464, "y": 40.09274701977745, "z": 203.01785550443304, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.858742816221562, "steering_wheel_angle": 9.987, "front_wheel_angle": 0.5426302360242441, "heading_rate": 0.8362061039610988, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059743.529575}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.55, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.987, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059743.529575}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059743.6299534, "x": -88.23608644084551, "y": 40.09274214494437, "z": 203.01382712824991, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8503218162215616, "steering_wheel_angle": 9.96, "front_wheel_angle": 0.5408357083761002, "heading_rate": 0.8163946569819996, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059743.6296208}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.96, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059743.6296208}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059743.7298682, "x": -88.23608644084551, "y": 40.09274214494437, "z": 203.01382712824991, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8443668162215614, "steering_wheel_angle": 9.837, "front_wheel_angle": 0.5326940322995258, "heading_rate": 0.7898936722923253, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059743.7295542}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.837, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059743.7295542}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059743.8298397, "x": -88.23608644084551, "y": 40.09274214494437, "z": 203.01382712824991, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8384618162215616, "steering_wheel_angle": 9.655, "front_wheel_angle": 0.5207456839104201, "heading_rate": 0.7572683933845511, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059743.8295605}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.655, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059743.8295605}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059743.929727, "x": -88.23608644084551, "y": 40.09274214494437, "z": 203.01382712824991, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8672618162215615, "steering_wheel_angle": 9.367, "front_wheel_angle": 0.5020715750063977, "heading_rate": 0.7763137659243895, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059743.9295318}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059743.9295318}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059744.0297472, "x": -88.23608644084551, "y": 40.09274214494437, "z": 203.01382712824991, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8503218162215616, "steering_wheel_angle": 8.877, "front_wheel_angle": 0.4709245799256732, "heading_rate": 0.6920980400729938, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059744.0295465}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.877, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059744.0295465}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059744.1297133, "x": -88.23607000096425, "y": 40.09274064102984, "z": 203.06117310671303, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8796018162215615, "steering_wheel_angle": 8.055, "front_wheel_angle": 0.4203078132417915, "heading_rate": 0.6494622981537825, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059744.1295297}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.055, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059744.1295297}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059744.2296875, "x": -88.23607000096425, "y": 40.09274064102984, "z": 203.06117310671303, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8734068162215616, "steering_wheel_angle": 7.269, "front_wheel_angle": 0.3736439656774203, "heading_rate": 0.5620565857871929, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059744.2295203}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.269, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059744.2295203}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059744.329737, "x": -88.23607000096425, "y": 40.09274064102984, "z": 203.06117310671303, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9217428162215615, "steering_wheel_angle": 6.568, "front_wheel_angle": 0.3333198654170099, "heading_rate": 0.5477600747075224, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059744.3295202}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.568, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059744.3295202}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059744.4298043, "x": -88.23607000096425, "y": 40.09274064102984, "z": 203.06117310671303, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9113268162215618, "steering_wheel_angle": 6.05, "front_wheel_angle": 0.304243540579259, "heading_rate": 0.48693288986015204, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059744.4295564}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.05, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059744.4295564}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059744.5296795, "x": -88.23607000096425, "y": 40.09274064102984, "z": 203.06117310671303, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9483428162215617, "steering_wheel_angle": 6.02, "front_wheel_angle": 0.3025774402318133, "heading_rate": 0.5182386614948702, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059744.5295172}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.25, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.02, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059744.5295172}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059744.6297784, "x": -88.23605025945186, "y": 40.09274162178576, "z": 203.07054967441155, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9633138162215618, "steering_wheel_angle": 6.023, "front_wheel_angle": 0.30274396413208526, "heading_rate": 0.5319631612513166, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059744.6295378}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.023, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059744.6295378}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059744.7297802, "x": -88.23605025945186, "y": 40.09274162178576, "z": 203.07054967441155, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.015446816221562, "steering_wheel_angle": 5.827, "front_wheel_angle": 0.2919042882563194, "heading_rate": 0.5551982240620814, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059744.729531}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.73, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.827, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059744.729531}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059744.8299162, "x": -88.23605025945186, "y": 40.09274162178576, "z": 203.07054967441155, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": 5.317, "front_wheel_angle": 0.26406878920885074, "heading_rate": 0.4921815795855281, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059744.829574}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059744.829574}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059744.929742, "x": -88.23605025945186, "y": 40.09274162178576, "z": 203.07054967441155, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": 4.523, "front_wheel_angle": 0.22173953131359497, "heading_rate": 0.4464900487644664, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059744.9295373}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.523, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059744.9295373}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059745.0296984, "x": -88.23605025945186, "y": 40.09274162178576, "z": 203.07054967441155, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": 3.722, "front_wheel_angle": 0.18019101051653605, "heading_rate": 0.3664685106880734, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059745.0295396}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.722, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059745.0295396}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059745.129757, "x": -88.23602567841148, "y": 40.09274638816492, "z": 203.07720435220207, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": 2.973, "front_wheel_angle": 0.14230914944078885, "heading_rate": 0.2927118076396866, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059745.129531}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.973, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059745.129531}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059745.229867, "x": -88.23602567841148, "y": 40.09274638816492, "z": 203.07720435220207, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": 2.183, "front_wheel_angle": 0.10329599502129198, "heading_rate": 0.22190780807510085, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059745.229552}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.183, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059745.229552}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059745.3297522, "x": -88.23602567841148, "y": 40.09274638816492, "z": 203.07720435220207, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": 1.388, "front_wheel_angle": 0.06494591233966261, "heading_rate": 0.14531789594278785, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059745.329526}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.388, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059745.329526}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059745.4297063, "x": -88.23602567841148, "y": 40.09274638816492, "z": 203.07720435220207, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1966388162215615, "steering_wheel_angle": 0.679, "front_wheel_angle": 0.031464937616009624, "heading_rate": 0.07241783898481541, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059745.4295177}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.679, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059745.4295177}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059745.5304532, "x": -88.23602567841148, "y": 40.09274638816492, "z": 203.07720435220207, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.223742816221561, "steering_wheel_angle": 0.267, "front_wheel_angle": 0.012304955160745193, "heading_rate": 0.029081537592124933, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059745.529602}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.267, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059745.529602}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059745.6298945, "x": -88.23599560080851, "y": 40.0927548441613, "z": 203.07332838041694, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.2531018162215615, "steering_wheel_angle": 0.435, "front_wheel_angle": 0.020092183668524888, "heading_rate": 0.04882429773931659, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059745.6295462}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.435, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059745.6295462}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059745.7296743, "x": -88.23599560080851, "y": 40.0927548441613, "z": 203.07332838041694, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.267117816221561, "steering_wheel_angle": 1.028, "front_wheel_angle": 0.047863539813991364, "heading_rate": 0.1178792109816506, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059745.729515}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.028, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059745.729515}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059745.829682, "x": -88.23599560080851, "y": 40.0927548441613, "z": 203.07332838041694, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": 1.651, "front_wheel_angle": 0.07753562797905675, "heading_rate": 0.19604933685045928, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059745.8295138}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.651, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059745.8295138}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059745.9298298, "x": -88.23599560080851, "y": 40.0927548441613, "z": 203.07332838041694, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": 1.873, "front_wheel_angle": 0.08823679015121737, "heading_rate": 0.22323968748239253, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059745.9295654}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.873, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059745.9295654}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059746.0299125, "x": -88.23599560080851, "y": 40.0927548441613, "z": 203.07332838041694, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.324461816221562, "steering_wheel_angle": 1.604, "front_wheel_angle": 0.07527882171769179, "heading_rate": 0.19503488175072878, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059746.029572}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.604, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059746.029572}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059746.1298852, "x": -88.23596181064728, "y": 40.092765406968226, "z": 203.10127144100915, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3099338162215615, "steering_wheel_angle": 1.252, "front_wheel_angle": 0.05847233172025178, "heading_rate": 0.149549010501695, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059746.1295686}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.54, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.252, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059746.1295686}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059746.2297611, "x": -88.23596181064728, "y": 40.092765406968226, "z": 203.10127144100915, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": 1.273, "front_wheel_angle": 0.05947031321004078, "heading_rate": 0.15978257391300613, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059746.2295794}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059746.2295794}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059746.3299298, "x": -88.23596181064728, "y": 40.092765406968226, "z": 203.10127144100915, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.340958816221562, "steering_wheel_angle": 1.614, "front_wheel_angle": 0.07575873894590278, "heading_rate": 0.19895152277003453, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059746.3295698}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.614, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059746.3295698}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059746.4299843, "x": -88.23596181064728, "y": 40.092765406968226, "z": 203.10127144100915, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": 1.933, "front_wheel_angle": 0.09114082482998256, "heading_rate": 0.24812049611684897, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059746.4296224}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.933, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059746.4296224}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059746.5297205, "x": -88.23596181064728, "y": 40.092765406968226, "z": 203.10127144100915, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": 2.007, "front_wheel_angle": 0.0947294717805623, "heading_rate": 0.2579477559819027, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059746.5295231}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.007, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059746.5295231}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059746.6297328, "x": -88.23592708012048, "y": 40.09277823569101, "z": 203.12702386187772, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": 1.832, "front_wheel_angle": 0.0862552765869303, "heading_rate": 0.23475207051471103, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059746.629547}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.832, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059746.629547}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059746.7297106, "x": -88.23592708012048, "y": 40.09277823569101, "z": 203.12702386187772, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": 1.434, "front_wheel_angle": 0.067141131716453, "heading_rate": 0.18911869644015705, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059746.7295232}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.434, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059746.7295232}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059746.8298686, "x": -88.23592708012048, "y": 40.09277823569101, "z": 203.12702386187772, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": 0.923, "front_wheel_angle": 0.04291332422162926, "heading_rate": 0.11942600177961699, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059746.8295908}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.923, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059746.8295908}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059746.9299111, "x": -88.23592708012048, "y": 40.09277823569101, "z": 203.12702386187772, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": 0.328, "front_wheel_angle": 0.015128425973890674, "heading_rate": 0.0425519443786172, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059746.9295766}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.328, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059746.9295766}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059747.029712, "x": -88.23592708012048, "y": 40.09277823569101, "z": 203.12702386187772, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.449201816221562, "steering_wheel_angle": -0.311, "front_wheel_angle": -0.014341096197796534, "heading_rate": -0.040785288414005166, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059747.0295203}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.311, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059747.0295203}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059747.12977, "x": -88.23589249222718, "y": 40.092794768579346, "z": 203.1633432704709, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.449201816221562, "steering_wheel_angle": -0.967, "front_wheel_angle": -0.04498595390745464, "heading_rate": -0.1280151743851342, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059747.129553}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.967, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059747.129553}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059747.2297308, "x": -88.23589249222718, "y": 40.092794768579346, "z": 203.1633432704709, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.464913816221562, "steering_wheel_angle": -1.583, "front_wheel_angle": -0.07427144212850702, "heading_rate": -0.2139238932037128, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059747.229552}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.583, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059747.229552}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059747.3297207, "x": -88.23589249222718, "y": 40.092794768579346, "z": 203.1633432704709, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.496721816221561, "steering_wheel_angle": -2.076, "front_wheel_angle": -0.09808265361756525, "heading_rate": -0.2890452818149336, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059747.329548}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.076, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059747.329548}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059747.4297009, "x": -88.23589249222718, "y": 40.092794768579346, "z": 203.1633432704709, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.496721816221561, "steering_wheel_angle": -2.382, "front_wheel_angle": -0.11303590883460948, "heading_rate": -0.3334644314291159, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059747.4295454}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.382, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059747.4295454}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059747.5296824, "x": -88.23589249222718, "y": 40.092794768579346, "z": 203.1633432704709, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.514838816221562, "steering_wheel_angle": -2.645, "front_wheel_angle": -0.1259977067172325, "heading_rate": -0.3765425731959768, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059747.5295386}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.645, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059747.5295386}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059747.6296573, "x": -88.2358546999251, "y": 40.0928114264104, "z": 203.19063538877083, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.514838816221562, "steering_wheel_angle": -2.814, "front_wheel_angle": -0.13438154971127786, "heading_rate": -0.40189224819580943, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059747.6295164}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.814, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059747.6295164}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059747.7297075, "x": -88.2358546999251, "y": 40.0928114264104, "z": 203.19063538877083, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.531078816221561, "steering_wheel_angle": -2.86, "front_wheel_angle": -0.13667107177788965, "heading_rate": -0.4131225316249242, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059747.729541}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.86, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059747.729541}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059747.829793, "x": -88.2358546999251, "y": 40.0928114264104, "z": 203.19063538877083, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.547446816221561, "steering_wheel_angle": -2.868, "front_wheel_angle": -0.13706958066826355, "heading_rate": -0.41865277690917874, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059747.8295298}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.868, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059747.8295298}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059747.929797, "x": -88.2358546999251, "y": 40.0928114264104, "z": 203.19063538877083, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.547446816221561, "steering_wheel_angle": -2.944, "front_wheel_angle": -0.1408603282965549, "heading_rate": -0.43038338112152746, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059747.9295447}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.944, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059747.9295447}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059748.029808, "x": -88.2358546999251, "y": 40.0928114264104, "z": 203.19063538877083, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.563942816221561, "steering_wheel_angle": -3.098, "front_wheel_angle": -0.14856904146229516, "heading_rate": -0.45895481663672694, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059748.029548}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.098, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059748.029548}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059748.129882, "x": -88.23581130371042, "y": 40.09282247856555, "z": 203.19544418375997, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.563942816221561, "steering_wheel_angle": -3.261, "front_wheel_angle": -0.15676881881172522, "heading_rate": -0.4846940955358027, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059748.1295667}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.261, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059748.1295667}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059748.2297616, "x": -88.23581130371042, "y": 40.09282247856555, "z": 203.19544418375997, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.580566816221562, "steering_wheel_angle": -3.328, "front_wheel_angle": -0.1601515208558921, "heading_rate": -0.500379690159326, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059748.229525}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.328, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059748.229525}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059748.3298507, "x": -88.23581130371042, "y": 40.09282247856555, "z": 203.19544418375997, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.580566816221562, "steering_wheel_angle": -3.325, "front_wheel_angle": -0.1599999029681552, "heading_rate": -0.4998977867688824, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059748.3295295}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.325, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059748.3295295}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059748.4296741, "x": -88.23581130371042, "y": 40.09282247856555, "z": 203.19544418375997, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.580566816221562, "steering_wheel_angle": -3.325, "front_wheel_angle": -0.1599999029681552, "heading_rate": -0.4998977867688824, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059748.429519}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.325, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059748.429519}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059748.5297356, "x": -88.23581130371042, "y": 40.09282247856555, "z": 203.19544418375997, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": -3.342, "front_wheel_angle": -0.1608592619092854, "heading_rate": -0.5083339882273494, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059748.529547}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.342, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059748.529547}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059748.629855, "x": -88.23576460516603, "y": 40.09282604295033, "z": 203.1836578192689, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": -3.396, "front_wheel_angle": -0.16359207239060883, "heading_rate": -0.5171247011248704, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059748.6295266}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.396, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059748.6295266}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059748.7299743, "x": -88.23576460516603, "y": 40.09282604295033, "z": 203.1836578192689, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": -3.463, "front_wheel_angle": -0.16698932746456965, "heading_rate": -0.5333313012749631, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059748.7295923}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059748.7295923}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059748.8296769, "x": -88.23576460516603, "y": 40.09282604295033, "z": 203.1836578192689, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": -3.461, "front_wheel_angle": -0.1668878115013023, "heading_rate": -0.5330009780112314, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059748.8295121}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.461, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059748.8295121}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059748.9297965, "x": -88.23576460516603, "y": 40.09282604295033, "z": 203.1836578192689, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": -3.35, "front_wheel_angle": -0.16126382665806868, "heading_rate": -0.5096348688684799, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059748.9295962}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.35, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059748.9295962}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059749.0297441, "x": -88.23576460516603, "y": 40.09282604295033, "z": 203.1836578192689, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": -3.123, "front_wheel_angle": -0.1498239530519602, "heading_rate": -0.4776315440433499, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059749.0295317}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.123, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059749.0295317}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059749.1296797, "x": -88.23571730060358, "y": 40.092820665879366, "z": 203.15162641836255, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": -2.752, "front_wheel_angle": -0.13130078654196542, "heading_rate": -0.4137209846840736, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059749.1295455}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.752, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059749.1295455}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059749.2298052, "x": -88.23571730060358, "y": 40.092820665879366, "z": 203.15162641836255, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": -2.225, "front_wheel_angle": -0.10534686159995135, "heading_rate": -0.3312583030711638, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059749.2296057}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.225, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059749.2296057}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059749.329743, "x": -88.23571730060358, "y": 40.092820665879366, "z": 203.15162641836255, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": -1.555, "front_wheel_angle": -0.07292920895811172, "heading_rate": -0.22887945946017182, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059749.3295395}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.555, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059749.3295395}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059749.4298272, "x": -88.23571730060358, "y": 40.092820665879366, "z": 203.15162641836255, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.580566816221562, "steering_wheel_angle": -0.87, "front_wheel_angle": -0.04042007806052882, "heading_rate": -0.12527573930740787, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059749.4295444}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.87, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059749.4295444}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059749.5301614, "x": -88.23571730060358, "y": 40.092820665879366, "z": 203.15162641836255, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.580566816221562, "steering_wheel_angle": -0.331, "front_wheel_angle": -0.015267403553108584, "heading_rate": -0.04729684295864147, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059749.5296755}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.331, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059749.5296755}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059749.6297445, "x": -88.23567255592087, "y": 40.09280844873795, "z": 203.19359328841958, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.563942816221561, "steering_wheel_angle": 0.082, "front_wheel_angle": 0.003769840040269683, "heading_rate": 0.011559915823030266, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059749.6295757}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.082, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059749.6295757}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059749.7298422, "x": -88.23567255592087, "y": 40.09280844873795, "z": 203.19359328841958, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.580566816221562, "steering_wheel_angle": 0.488, "front_wheel_angle": 0.022556140498582317, "heading_rate": 0.06988302167566499, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059749.729589}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.488, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059749.729589}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059749.8296347, "x": -88.23567255592087, "y": 40.09280844873795, "z": 203.19359328841958, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": 0.97, "front_wheel_angle": 0.04512736116406351, "heading_rate": 0.14147160882804188, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059749.829505}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.97, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059749.829505}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059749.9296684, "x": -88.23567255592087, "y": 40.09280844873795, "z": 203.19359328841958, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.580566816221562, "steering_wheel_angle": 1.389, "front_wheel_angle": 0.06499360414333141, "heading_rate": 0.201611804811184, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059749.9295287}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.389, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059749.9295287}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059750.0297363, "x": -88.23567255592087, "y": 40.09280844873795, "z": 203.19359328841958, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.563942816221561, "steering_wheel_angle": 1.739, "front_wheel_angle": 0.08176933255227022, "heading_rate": 0.25129832114395423, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059750.029556}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.739, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059750.029556}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059750.1296952, "x": -88.23562974204484, "y": 40.092796634301614, "z": 203.15179246344613, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.547446816221561, "steering_wheel_angle": 2.145, "front_wheel_angle": 0.10144264355046939, "heading_rate": 0.3089547790584329, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059750.129536}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.145, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059750.129536}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059750.2296784, "x": -88.23562974204484, "y": 40.092796634301614, "z": 203.15179246344613, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.531078816221561, "steering_wheel_angle": 2.511, "front_wheel_angle": 0.11938074566515935, "heading_rate": 0.3603219374832598, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059750.2295303}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.511, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059750.2295303}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059750.329688, "x": -88.23562974204484, "y": 40.092796634301614, "z": 203.15179246344613, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.563942816221561, "steering_wheel_angle": 2.743, "front_wheel_angle": 0.13085406530301597, "heading_rate": 0.40355770139732133, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059750.3295443}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.743, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059750.3295443}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059750.4299214, "x": -88.23562974204484, "y": 40.092796634301614, "z": 203.15179246344613, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.547446816221561, "steering_wheel_angle": 2.865, "front_wheel_angle": 0.13692012831840034, "heading_rate": 0.41819054482611406, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059750.4295769}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.865, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059750.4295769}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059750.5296547, "x": -88.23562974204484, "y": 40.092796634301614, "z": 203.15179246344613, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.531078816221561, "steering_wheel_angle": 2.885, "front_wheel_angle": 0.13791673854752062, "heading_rate": 0.4169358269880419, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059750.5295057}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.885, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059750.5295057}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059750.629696, "x": -88.23558674328811, "y": 40.09279079257622, "z": 203.16328481193062, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.514838816221562, "steering_wheel_angle": 2.905, "front_wheel_angle": 0.13891396413778212, "heading_rate": 0.4156203302163025, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059750.6295428}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.905, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059750.6295428}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059750.7296984, "x": -88.23558674328811, "y": 40.09279079257622, "z": 203.16328481193062, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.496721816221561, "steering_wheel_angle": 2.941, "front_wheel_angle": 0.14071052455555302, "heading_rate": 0.4160868949414928, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059750.7295098}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.941, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059750.7295098}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059750.829708, "x": -88.23558674328811, "y": 40.09279079257622, "z": 203.16328481193062, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.480753816221561, "steering_wheel_angle": 2.988, "front_wheel_angle": 0.1430590513032493, "heading_rate": 0.41862511745859726, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059750.829537}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.988, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059750.829537}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059750.9297042, "x": -88.23558674328811, "y": 40.09279079257622, "z": 203.16328481193062, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.514838816221562, "steering_wheel_angle": 3.029, "front_wheel_angle": 0.14511056756653376, "heading_rate": 0.4344173109124559, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059750.9295413}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.029, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059750.9295413}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059751.0297434, "x": -88.23558674328811, "y": 40.09279079257622, "z": 203.16328481193062, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.496721816221561, "steering_wheel_angle": 3.077, "front_wheel_angle": 0.1475156737691783, "heading_rate": 0.4364980878104805, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059751.0295134}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.077, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059751.0295134}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059751.1297312, "x": -88.23554452987143, "y": 40.09279138539822, "z": 203.1956681633627, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.480753816221561, "steering_wheel_angle": 3.119, "front_wheel_angle": 0.14962310119424355, "heading_rate": 0.43811640898843507, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059751.1295524}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.119, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059751.1295524}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059751.229712, "x": -88.23554452987143, "y": 40.09279138539822, "z": 203.1956681633627, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.464913816221562, "steering_wheel_angle": 3.126, "front_wheel_angle": 0.14997460846056065, "heading_rate": 0.43443908405744563, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059751.229548}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.126, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059751.229548}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059751.3297925, "x": -88.23554452987143, "y": 40.09279138539822, "z": 203.1956681633627, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.449201816221562, "steering_wheel_angle": 3.126, "front_wheel_angle": 0.14997460846056065, "heading_rate": 0.42971692010029955, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059751.3295703}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.126, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059751.3295703}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059751.429657, "x": -88.23554452987143, "y": 40.09279138539822, "z": 203.1956681633627, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": 3.127, "front_wheel_angle": 0.1500248300766564, "heading_rate": 0.4251392307991532, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059751.4295058}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.127, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059751.4295058}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059751.5297036, "x": -88.23554452987143, "y": 40.09279138539822, "z": 203.1956681633627, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.464913816221562, "steering_wheel_angle": 3.133, "front_wheel_angle": 0.15032619282248935, "heading_rate": 0.43547302479819305, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059751.5295}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.133, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059751.5295}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059751.6297665, "x": -88.23550477168348, "y": 40.09279856013765, "z": 203.2185611505861, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.449201816221562, "steering_wheel_angle": 3.138, "front_wheel_angle": 0.15057737173908656, "heading_rate": 0.43147032804311525, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059751.6295388}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.138, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059751.6295388}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059751.7296956, "x": -88.23550477168348, "y": 40.09279856013765, "z": 203.2185611505861, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": 3.138, "front_wheel_angle": 0.15057737173908656, "heading_rate": 0.42198746369051926, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059751.7295349}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.138, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059751.7295349}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059751.8300211, "x": -88.23550477168348, "y": 40.09279856013765, "z": 203.2185611505861, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": 3.135, "front_wheel_angle": 0.15042665966484528, "heading_rate": 0.42155865598504544, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059751.8297625}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.135, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059751.8297625}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059751.929657, "x": -88.23550477168348, "y": 40.09279856013765, "z": 203.2185611505861, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.400926816221562, "steering_wheel_angle": 3.107, "front_wheel_angle": 0.1490206965284341, "heading_rate": 0.4122811970893265, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059751.9295158}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.107, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059751.9295158}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059752.0297282, "x": -88.23550477168348, "y": 40.09279856013765, "z": 203.2185611505861, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.400926816221562, "steering_wheel_angle": 3.107, "front_wheel_angle": 0.1490206965284341, "heading_rate": 0.4122811970893265, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059752.02953}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.107, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059752.02953}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059752.1296933, "x": -88.23546894404241, "y": 40.09281159331154, "z": 201.60335005913905, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.400926816221562, "steering_wheel_angle": 2.968, "front_wheel_angle": 0.14205925972850791, "heading_rate": 0.3927536385754199, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059752.129534}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.968, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059752.129534}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059752.229636, "x": -88.23546894404241, "y": 40.09281159331154, "z": 203.2704014135622, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": 2.601, "front_wheel_angle": 0.12382200969805743, "heading_rate": 0.33788598701154626, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059752.229503}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.601, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059752.229503}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059752.3298798, "x": -88.23546894404241, "y": 40.09281159331154, "z": 203.2704014135622, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": 2.006, "front_wheel_angle": 0.09468092478738575, "heading_rate": 0.25484711725449105, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059752.3295388}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.006, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059752.3295388}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059752.429771, "x": -88.23546894404241, "y": 40.09281159331154, "z": 203.2704014135622, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.355758816221561, "steering_wheel_angle": 1.314, "front_wheel_angle": 0.061420450196340313, "heading_rate": 0.16311331225622264, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059752.4295213}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.314, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059752.4295213}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059752.5298042, "x": -88.23546894404241, "y": 40.09281159331154, "z": 203.2704014135622, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.355758816221561, "steering_wheel_angle": 0.634, "front_wheel_angle": 0.029361859998389816, "heading_rate": 0.07790013353232464, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059752.5295532}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.634, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059752.5295532}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059752.6297703, "x": -88.23543644508518, "y": 40.092828678079435, "z": 203.26081510654816, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.355758816221561, "steering_wheel_angle": 0.016, "front_wheel_angle": 0.0007349416638626075, "heading_rate": 0.001949318279728371, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059752.6295671}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059752.6295671}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059752.7297208, "x": -88.23543644508518, "y": 40.092828678079435, "z": 203.26081510654816, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.340958816221562, "steering_wheel_angle": -0.622, "front_wheel_angle": -0.028801472541920926, "heading_rate": -0.07551224058447624, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059752.7295434}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.622, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059752.7295434}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059752.8297052, "x": -88.23543644508518, "y": 40.092828678079435, "z": 203.26081510654816, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.340958816221562, "steering_wheel_angle": -1.295, "front_wheel_angle": -0.06051644880155257, "heading_rate": -0.1588132037954984, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059752.8295078}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.295, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059752.8295078}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059752.9297514, "x": -88.23543644508518, "y": 40.092828678079435, "z": 203.26081510654816, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3099338162215615, "steering_wheel_angle": -1.941, "front_wheel_angle": -0.09152841296939267, "heading_rate": -0.2344816446099414, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059752.9295442}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.54, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.941, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059752.9295442}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059753.029728, "x": -88.23543644508518, "y": 40.092828678079435, "z": 203.26081510654816, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": -2.497, "front_wheel_angle": -0.11869096712523894, "heading_rate": -0.29719704942779707, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059753.0295029}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.497, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059753.0295029}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059753.129896, "x": -88.23540351191993, "y": 40.0928448944009, "z": 203.23004262672612, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.223742816221561, "steering_wheel_angle": -2.914, "front_wheel_angle": -0.1393629167189229, "heading_rate": -0.3315027030085215, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059753.1295202}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.914, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059753.1295202}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059753.229835, "x": -88.23540351191993, "y": 40.0928448944009, "z": 203.23004262672612, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": -3.287, "front_wheel_angle": -0.15808065728842696, "heading_rate": -0.39728145191530223, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059753.2295616}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.287, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059753.2295616}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059753.3297787, "x": -88.23540351191993, "y": 40.0928448944009, "z": 203.23004262672612, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.210126816221561, "steering_wheel_angle": -3.698, "front_wheel_angle": -0.17896303374368078, "heading_rate": -0.42186078610615996, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059753.3295531}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.698, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059753.3295531}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059753.4297626, "x": -88.23540351191993, "y": 40.0928448944009, "z": 203.23004262672612, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.223742816221561, "steering_wheel_angle": -4.135, "front_wheel_angle": -0.2014747040499206, "heading_rate": -0.48269026329502773, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059753.4295192}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.135, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059753.4295192}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059753.5304027, "x": -88.23540351191993, "y": 40.0928448944009, "z": 203.23004262672612, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": -4.595, "front_wheel_angle": -0.22552958886726046, "heading_rate": -0.5126388424258743, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059753.5296013}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.595, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059753.5296013}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059753.6300333, "x": -88.23536929013177, "y": 40.09285492138962, "z": 203.24644183041087, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": -4.929, "front_wheel_angle": -0.24323568148616584, "heading_rate": -0.5467030161129647, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059753.6295943}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.929, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059753.6295943}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059753.7296734, "x": -88.23536929013177, "y": 40.09285492138962, "z": 203.24644183041087, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": -5.284, "front_wheel_angle": -0.26228557272234787, "heading_rate": -0.5663046483181652, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059753.7295294}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.284, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059753.7295294}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059753.829695, "x": -88.23536929013177, "y": 40.09285492138962, "z": 203.24644183041087, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": -5.666, "front_wheel_angle": -0.2830600662662621, "heading_rate": -0.5942390342167269, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059753.8295257}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059753.8295257}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059753.9298387, "x": -88.23536929013177, "y": 40.09285492138962, "z": 203.24644183041087, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": -6.045, "front_wheel_angle": -0.3039657241523697, "heading_rate": -0.6310496361522616, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059753.929543}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.045, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059753.929543}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059754.029702, "x": -88.23536929013177, "y": 40.09285492138962, "z": 203.24644183041087, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": -6.436, "front_wheel_angle": -0.3258542076417959, "heading_rate": -0.6586394938391764, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059754.0295324}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.436, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059754.0295324}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059754.1297169, "x": -88.23533716483581, "y": 40.09285693051218, "z": 203.27088133269837, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": -6.931, "front_wheel_angle": -0.3540558453535089, "heading_rate": -0.7089418668103742, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059754.1295302}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.931, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059754.1295302}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059754.2297199, "x": -88.23533716483581, "y": 40.09285693051218, "z": 203.27088133269837, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": -7.472, "front_wheel_angle": -0.3855432898837222, "heading_rate": -0.7514652764971158, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059754.2295442}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.472, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059754.2295442}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059754.3299417, "x": -88.23533716483581, "y": 40.09285693051218, "z": 203.27088133269837, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": -8.002, "front_wheel_angle": -0.41711001680170257, "heading_rate": -0.8637196467474876, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059754.3295262}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.002, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059754.3295262}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059754.4297352, "x": -88.23533716483581, "y": 40.09285693051218, "z": 203.27088133269837, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": -8.493, "front_wheel_angle": -0.44703459595765516, "heading_rate": -0.9026258263031357, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059754.4295285}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.493, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059754.4295285}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059754.5296357, "x": -88.23533716483581, "y": 40.09285693051218, "z": 203.27088133269837, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": -8.842, "front_wheel_angle": -0.468728700267708, "heading_rate": -0.9375712520622711, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059754.529493}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.842, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059754.529493}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059754.629632, "x": -88.23530948297683, "y": 40.092850943191834, "z": 203.208219121523, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": -9.205, "front_wheel_angle": -0.4916888833720474, "heading_rate": -0.9581493827589753, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059754.6294973}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.205, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059754.6294973}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059754.729751, "x": -88.23530948297683, "y": 40.092850943191834, "z": 203.208219121523, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": -9.568, "front_wheel_angle": -0.5150748507772338, "heading_rate": -0.9949929279331666, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059754.7295334}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.568, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059754.7295334}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059754.8298209, "x": -88.23530948297683, "y": 40.092850943191834, "z": 203.208219121523, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": -9.846, "front_wheel_angle": -0.5332879218626143, "heading_rate": -1.0561591186412052, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059754.8295462}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.846, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059754.8295462}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059754.9297314, "x": -88.23530948297683, "y": 40.092850943191834, "z": 203.208219121523, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": -10.051, "front_wheel_angle": -0.5468945967878859, "heading_rate": -1.108280156624124, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059754.9295523}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059754.9295523}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059755.0298972, "x": -88.23530948297683, "y": 40.092850943191834, "z": 203.208219121523, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": -10.303, "front_wheel_angle": -0.5638341602520625, "heading_rate": -1.13123078264201, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059755.029599}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.303, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059755.029599}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059755.1297529, "x": -88.23528893416784, "y": 40.09283751183342, "z": 203.13915160760976, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": -10.575, "front_wheel_angle": -0.5823931887752121, "heading_rate": -1.1345315553530613, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059755.129532}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.575, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059755.129532}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059755.2298157, "x": -88.23528893416784, "y": 40.09283751183342, "z": 203.13915160760976, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": -10.765, "front_wheel_angle": -0.5955337407072947, "heading_rate": -1.1672720069760132, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059755.2295697}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.765, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059755.2295697}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059755.3297133, "x": -88.23528893416784, "y": 40.09283751183342, "z": 203.13915160760976, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9592068162215615, "steering_wheel_angle": -10.876, "front_wheel_angle": -0.6032800891701446, "heading_rate": -1.1653162704449906, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059755.3295054}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059755.3295054}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059755.429886, "x": -88.23528893416784, "y": 40.09283751183342, "z": 203.13915160760976, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": -11.046, "front_wheel_angle": -0.6152461045384536, "heading_rate": -1.2423452921259708, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059755.4296753}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.046, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059755.4296753}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059755.5296774, "x": -88.23528893416784, "y": 40.09283751183342, "z": 203.13915160760976, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": -11.203, "front_wheel_angle": -0.6264099576049567, "heading_rate": -1.272006777293377, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059755.5295339}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.203, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059755.5295339}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059755.629654, "x": -88.23527817295839, "y": 40.092818778995365, "z": 203.06340918045646, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": -11.342, "front_wheel_angle": -0.636387030763985, "heading_rate": -1.272944883270123, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059755.6294951}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.342, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059755.6294951}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059755.729795, "x": -88.23527817295839, "y": 40.092818778995365, "z": 203.06340918045646, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": -11.366, "front_wheel_angle": -0.6381187299548031, "heading_rate": -1.2775628143216204, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059755.7295134}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.366, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059755.7295134}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059755.829707, "x": -88.23527817295839, "y": 40.092818778995365, "z": 203.06340918045646, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": -11.366, "front_wheel_angle": -0.6381187299548031, "heading_rate": -1.30363552481798, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059755.8294992}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.366, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059755.8294992}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059755.9296842, "x": -88.23527817295839, "y": 40.092818778995365, "z": 203.06340918045646, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": -11.365, "front_wheel_angle": -0.6380465221220816, "heading_rate": -1.3729555322894456, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059755.929528}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.365, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059755.929528}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059756.0298054, "x": -88.23527817295839, "y": 40.092818778995365, "z": 203.06340918045646, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9376068162215616, "steering_wheel_angle": -11.34, "front_wheel_angle": -0.6362428437101606, "heading_rate": -1.2033058966020511, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059756.0296276}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.17, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.34, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059756.0296276}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059756.1299572, "x": -88.23527876366546, "y": 40.092798726461915, "z": 202.96733889480927, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": -11.288, "front_wheel_angle": -0.6325004929283448, "heading_rate": -1.3342007917972896, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059756.1296446}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.288, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059756.1296446}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059756.2297077, "x": -88.23527876366546, "y": 40.092798726461915, "z": 202.96733889480927, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": -11.166, "front_wheel_angle": -0.6237690453267439, "heading_rate": -1.2396482184256914, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059756.2295616}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059756.2295616}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059756.3297713, "x": -88.23527876366546, "y": 40.092798726461915, "z": 202.96733889480927, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": -10.938, "front_wheel_angle": -0.6076296825741517, "heading_rate": -1.2875700875696907, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059756.3295016}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.938, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059756.3295016}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059756.4297783, "x": -88.23527876366546, "y": 40.092798726461915, "z": 202.96733889480927, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": -10.668, "front_wheel_angle": -0.5888066107467324, "heading_rate": -1.1739175197696425, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059756.4295506}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.668, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059756.4295506}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059756.5297112, "x": -88.23527876366546, "y": 40.092798726461915, "z": 202.96733889480927, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": -10.269, "front_wheel_angle": -0.5615346083555754, "heading_rate": -1.1647983530048487, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059756.5295174}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.269, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059756.5295174}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059756.6297743, "x": -88.23529119174583, "y": 40.092780259824586, "z": 202.90131809393355, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": -9.845, "front_wheel_angle": -0.5332219198538601, "heading_rate": -1.0744453041295958, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059756.6295698}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.845, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059756.6295698}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059756.7297037, "x": -88.23529119174583, "y": 40.092780259824586, "z": 202.90131809393355, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": -9.555, "front_wheel_angle": -0.5142297142935861, "heading_rate": -1.045994009820216, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059756.7295032}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.555, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059756.7295032}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059756.8298984, "x": -88.23529119174583, "y": 40.092780259824586, "z": 202.90131809393355, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": -9.312, "front_wheel_angle": -0.4985369519651303, "heading_rate": -1.0441504657743352, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059756.8295748}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.312, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059756.8295748}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059756.9297228, "x": -88.23529119174583, "y": 40.092780259824586, "z": 202.90131809393355, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": -8.979, "front_wheel_angle": -0.4773455603470934, "heading_rate": -0.9920532343952756, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059756.929539}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.979, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059756.929539}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059757.0296655, "x": -88.23529119174583, "y": 40.092780259824586, "z": 202.90131809393355, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": -8.467, "front_wheel_angle": -0.44543282243254395, "heading_rate": -0.9455441742269339, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059757.0295258}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.467, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059757.0295258}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059757.1297593, "x": -88.2353138819121, "y": 40.09276581464453, "z": 202.82789418104406, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": -7.827, "front_wheel_angle": -0.40660519597655065, "heading_rate": -0.8527919005293532, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059757.1295319}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.827, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059757.1295319}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059757.22999, "x": -88.2353138819121, "y": 40.09276581464453, "z": 202.82789418104406, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": -7.219, "front_wheel_angle": -0.37072882025143444, "heading_rate": -0.8062526888272477, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059757.2295477}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.219, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059757.2295477}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059757.3297248, "x": -88.2353138819121, "y": 40.09276581464453, "z": 202.82789418104406, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": -6.961, "front_wheel_angle": -0.3557833303877747, "heading_rate": -0.770772154452137, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059757.3295436}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.961, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059757.3295436}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059757.4297009, "x": -88.2353138819121, "y": 40.09276581464453, "z": 202.82789418104406, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.142353816221561, "steering_wheel_angle": -6.937, "front_wheel_angle": -0.3544011716607485, "heading_rate": -0.8036462272774085, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059757.4295132}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.937, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059757.4295132}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059757.5299149, "x": -88.2353138819121, "y": 40.09276581464453, "z": 202.82789418104406, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": -6.756, "front_wheel_angle": -0.34402106210768124, "heading_rate": -0.8005040874543818, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059757.529545}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.756, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059757.529545}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059757.6299715, "x": -88.23534430668725, "y": 40.09275679712412, "z": 202.80711597519755, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.183278816221561, "steering_wheel_angle": -6.237, "front_wheel_angle": -0.3146724078671413, "heading_rate": -0.7387031614698941, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059757.629557}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.237, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059757.629557}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059757.729722, "x": -88.23534430668725, "y": 40.09275679712412, "z": 202.80711597519755, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1966388162215615, "steering_wheel_angle": -5.534, "front_wheel_angle": -0.2758484081550739, "heading_rate": -0.6512701453679536, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059757.7295291}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.534, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059757.7295291}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059757.8296745, "x": -88.23534430668725, "y": 40.09275679712412, "z": 202.80711597519755, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.210126816221561, "steering_wheel_angle": -4.734, "front_wheel_angle": -0.23287323663045661, "heading_rate": -0.5531022341900025, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059757.8295286}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.734, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059757.8295286}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059757.9298222, "x": -88.23534430668725, "y": 40.09275679712412, "z": 202.80711597519755, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.2531018162215615, "steering_wheel_angle": -3.962, "front_wheel_angle": -0.19252392599040954, "heading_rate": -0.4736393752936281, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059757.929534}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.962, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059757.929534}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059758.0298553, "x": -88.23534430668725, "y": 40.09275679712412, "z": 202.80711597519755, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.267117816221561, "steering_wheel_angle": -3.294, "front_wheel_angle": -0.15843402897011055, "heading_rate": -0.3931916409444596, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059758.0295372}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.294, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059758.0295372}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059758.1296945, "x": -88.23538023795871, "y": 40.09275386934687, "z": 202.81673003910475, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": -2.655, "front_wheel_angle": -0.12649258919959822, "heading_rate": -0.31693541734855274, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059758.1295078}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.655, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059758.1295078}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059758.2296941, "x": -88.23538023795871, "y": 40.09275386934687, "z": 202.81673003910475, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3099338162215615, "steering_wheel_angle": -1.943, "front_wheel_angle": -0.09162532413285288, "heading_rate": -0.234731310278455, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059758.2295084}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.54, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.943, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059758.2295084}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059758.3299272, "x": -88.23538023795871, "y": 40.09275386934687, "z": 202.81673003910475, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.324461816221562, "steering_wheel_angle": -1.239, "front_wheel_angle": -0.057854828095665646, "heading_rate": -0.1497761160935611, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059758.329553}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.239, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059758.329553}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059758.4298303, "x": -88.23538023795871, "y": 40.09275386934687, "z": 202.81673003910475, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.340958816221562, "steering_wheel_angle": -0.589, "front_wheel_angle": -0.027261345335914174, "heading_rate": -0.07147224835831609, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059758.429536}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.589, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059758.429536}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059758.5297394, "x": -88.23538023795871, "y": 40.09275386934687, "z": 202.81673003910475, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": -0.174, "front_wheel_angle": -0.008009111419146078, "heading_rate": -0.02149366092593528, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059758.5295153}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.174, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059758.5295153}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059758.6296468, "x": -88.23541944666624, "y": 40.09275450795097, "z": 202.82037641724375, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.400926816221562, "steering_wheel_angle": 0.016, "front_wheel_angle": 0.0007349416638626075, "heading_rate": 0.0020182190731208322, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059758.629498}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059758.629498}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059758.729678, "x": -88.23541944666624, "y": 40.09275450795097, "z": 202.82037641724375, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": 0.23, "front_wheel_angle": 0.010594587371297717, "heading_rate": 0.029467298656416972, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059758.7295089}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.23, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059758.7295089}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059758.8296895, "x": -88.23541944666624, "y": 40.09275450795097, "z": 202.82037641724375, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": 0.356, "front_wheel_angle": 0.016425982587696047, "heading_rate": 0.046202231422050946, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059758.8295321}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.356, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059758.8295321}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059758.9299164, "x": -88.23541944666624, "y": 40.09275450795097, "z": 202.82037641724375, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.449201816221562, "steering_wheel_angle": 0.404, "front_wheel_angle": 0.01865262390966145, "heading_rate": 0.05304955172584849, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059758.9295847}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.404, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059758.9295847}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059759.0297196, "x": -88.23541944666624, "y": 40.09275450795097, "z": 202.82037641724375, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.480753816221561, "steering_wheel_angle": 0.434, "front_wheel_angle": 0.020045727591179327, "heading_rate": 0.058265700346266956, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059759.02954}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.434, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059759.02954}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059759.1297524, "x": -88.23546124705483, "y": 40.09275449426107, "z": 202.7926762580589, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.496721816221561, "steering_wheel_angle": 0.478, "front_wheel_angle": 0.022090974520479194, "heading_rate": 0.06490279576019027, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059759.1295328}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.478, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059759.1295328}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059759.2297456, "x": -88.23546124705483, "y": 40.09275449426107, "z": 202.7926762580589, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.514838816221562, "steering_wheel_angle": 0.501, "front_wheel_angle": 0.023161043276796894, "heading_rate": 0.06886213382192444, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059759.2295191}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.501, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059759.2295191}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059759.3296177, "x": -88.23546124705483, "y": 40.09275449426107, "z": 202.7926762580589, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.531078816221561, "steering_wheel_angle": 0.444, "front_wheel_angle": 0.02051034442199724, "heading_rate": 0.06161979266080097, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059759.329497}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059759.329497}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059759.4296737, "x": -88.23546124705483, "y": 40.09275449426107, "z": 202.7926762580589, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.547446816221561, "steering_wheel_angle": 0.378, "front_wheel_angle": 0.017446171916289166, "heading_rate": 0.0529572306842645, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059759.4295285}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.378, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059759.4295285}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059759.5296848, "x": -88.23546124705483, "y": 40.09275449426107, "z": 202.7926762580589, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.563942816221561, "steering_wheel_angle": 0.33, "front_wheel_angle": 0.015221076458394224, "heading_rate": 0.04667760881374476, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059759.5295327}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.33, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059759.5295327}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059759.629722, "x": -88.23550555738376, "y": 40.092752987403465, "z": 202.7796961508076, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": 0.356, "front_wheel_angle": 0.016425982587696047, "heading_rate": 0.05146415222289564, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059759.6295369}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.356, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059759.6295369}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059759.7298317, "x": -88.23550555738376, "y": 40.092752987403465, "z": 202.7796961508076, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": 0.371, "front_wheel_angle": 0.017121501183618642, "heading_rate": 0.054178794037616315, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059759.7295163}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.371, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059759.7295163}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059759.829722, "x": -88.23550555738376, "y": 40.092752987403465, "z": 202.7796961508076, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.633341816221561, "steering_wheel_angle": 0.361, "front_wheel_angle": 0.01665779116363142, "heading_rate": 0.05323177203826186, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059759.8295112}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059759.8295112}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059759.9297514, "x": -88.23550555738376, "y": 40.092752987403465, "z": 202.7796961508076, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.633341816221561, "steering_wheel_angle": 0.345, "front_wheel_angle": 0.015916112610280052, "heading_rate": 0.050861248416152756, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059759.9295547}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.345, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059759.9295547}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059760.0301788, "x": -88.23550555738376, "y": 40.092752987403465, "z": 202.7796961508076, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.667773816221562, "steering_wheel_angle": 0.33, "front_wheel_angle": 0.015221076458394224, "heading_rate": 0.04959124299447532, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059760.0296128}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.33, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059760.0296128}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059760.1296613, "x": -88.23555239155472, "y": 40.09275018509918, "z": 202.80575765538595, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.667773816221562, "steering_wheel_angle": 0.324, "front_wheel_angle": 0.01494313982181801, "heading_rate": 0.04868557154234419, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059760.129523}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.324, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059760.129523}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059760.2296617, "x": -88.23555239155472, "y": 40.09275018509918, "z": 202.80575765538595, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.687366816221561, "steering_wheel_angle": 0.31, "front_wheel_angle": 0.014294793784490093, "heading_rate": 0.04707551575171979, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059760.2295241}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.31, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059760.2295241}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059760.3296907, "x": -88.23555239155472, "y": 40.09275018509918, "z": 202.80575765538595, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.704918816221562, "steering_wheel_angle": 0.261, "front_wheel_angle": 0.012027484072861203, "heading_rate": 0.03998391611833399, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059760.3295305}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.51, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.261, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059760.3295305}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059760.4298263, "x": -88.23555239155472, "y": 40.09275018509918, "z": 202.80575765538595, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.704918816221562, "steering_wheel_angle": 0.198, "front_wheel_angle": 0.009116703161574537, "heading_rate": 0.030306755233887945, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059760.429521}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.51, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.198, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059760.429521}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059760.5298913, "x": -88.23555239155472, "y": 40.09275018509918, "z": 202.80575765538595, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.722598816221561, "steering_wheel_angle": 0.128, "front_wheel_angle": 0.005888189917356626, "heading_rate": 0.019757865602490196, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059760.5295694}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.59, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.128, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059760.5295694}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059760.6296918, "x": -88.23560152023217, "y": 40.09274629270944, "z": 202.8136168367426, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.740406816221562, "steering_wheel_angle": 0.026, "front_wheel_angle": 0.001194436781101673, "heading_rate": 0.004045223365992241, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059760.629508}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059760.629508}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059760.7298126, "x": -88.23560152023217, "y": 40.09274629270944, "z": 202.8136168367426, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.758342816221561, "steering_wheel_angle": -0.073, "front_wheel_angle": -0.003355680274479731, "heading_rate": -0.011469653364883856, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059760.7295337}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.75, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.073, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059760.7295337}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059760.8296974, "x": -88.23560152023217, "y": 40.09274629270944, "z": 202.8136168367426, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.776406816221561, "steering_wheel_angle": -0.106, "front_wheel_angle": -0.004874745792685537, "heading_rate": -0.01681419777590748, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059760.829519}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.106, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059760.829519}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059760.9297464, "x": -88.23560152023217, "y": 40.09274629270944, "z": 202.8136168367426, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.776406816221561, "steering_wheel_angle": -0.095, "front_wheel_angle": -0.004368243991637956, "heading_rate": -0.015067124915381513, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059760.929587}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.095, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059760.929587}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059761.0297804, "x": -88.23560152023217, "y": 40.09274629270944, "z": 202.8136168367426, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.796881816221561, "steering_wheel_angle": -0.089, "front_wheel_angle": -0.0040920321100195315, "heading_rate": -0.014258253966960534, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059761.0295186}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.089, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059761.0295186}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059761.1296704, "x": -88.2356526228377, "y": 40.092742202954014, "z": 202.79859924143472, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.833681816221562, "steering_wheel_angle": -0.089, "front_wheel_angle": -0.0040920321100195315, "heading_rate": -0.01451400740134548, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059761.1295164}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.089, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059761.1295164}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059761.2296934, "x": -88.2356526228377, "y": 40.092742202954014, "z": 202.79859924143472, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.833681816221562, "steering_wheel_angle": -0.104, "front_wheel_angle": -0.004782643640989698, "heading_rate": -0.01696356850407955, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059761.2295036}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.104, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059761.2295036}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059761.3296974, "x": -88.2356526228377, "y": 40.092742202954014, "z": 202.79859924143472, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.852273816221562, "steering_wheel_angle": -0.116, "front_wheel_angle": -0.005335329359043072, "heading_rate": -0.019090656506387253, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059761.3295069}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.116, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059761.3295069}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059761.4296966, "x": -88.2356526228377, "y": 40.092742202954014, "z": 202.79859924143472, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.870993816221562, "steering_wheel_angle": -0.147, "front_wheel_angle": -0.006763910446322207, "heading_rate": -0.024413861583661996, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059761.4295087}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.147, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059761.4295087}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059761.5296957, "x": -88.2356526228377, "y": 40.092742202954014, "z": 202.79859924143472, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.870993816221562, "steering_wheel_angle": -0.175, "front_wheel_angle": -0.00805524703858198, "heading_rate": -0.029075036146606035, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059761.5295095}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.175, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059761.5295095}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059761.6298547, "x": -88.2357054820101, "y": 40.09273844736497, "z": 202.81312825118528, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": -0.169, "front_wheel_angle": -0.007778451616404846, "heading_rate": -0.02834938174816299, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059761.6295402}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.169, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059761.6295402}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059761.7297306, "x": -88.2357054820101, "y": 40.09273844736497, "z": 202.81312825118528, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.870993816221562, "steering_wheel_angle": -0.143, "front_wheel_angle": -0.006579511737334867, "heading_rate": -0.02374826786523707, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059761.7295215}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.143, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059761.7295215}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059761.829703, "x": -88.2357054820101, "y": 40.09273844736497, "z": 202.81312825118528, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.911198816221562, "steering_wheel_angle": -0.117, "front_wheel_angle": -0.005381394392021079, "heading_rate": -0.019781019554271053, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059761.829503}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.117, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059761.829503}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059761.9296222, "x": -88.2357054820101, "y": 40.09273844736497, "z": 202.81312825118528, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.930318816221561, "steering_wheel_angle": -0.114, "front_wheel_angle": -0.005243202935496302, "heading_rate": -0.019436895246678965, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059761.929491}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.49, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.114, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059761.929491}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059762.029671, "x": -88.2357054820101, "y": 40.09273844736497, "z": 202.81312825118528, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.930318816221561, "steering_wheel_angle": -0.114, "front_wheel_angle": -0.005243202935496302, "heading_rate": -0.019436895246678965, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059762.0295002}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.49, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.114, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059762.0295002}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059762.1298084, "x": -88.2357054820101, "y": 40.09273844736497, "z": 202.81312825118528, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.949566816221562, "steering_wheel_angle": -0.108, "front_wheel_angle": -0.004966852797216844, "heading_rate": -0.018567645369223604, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059762.1295145}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.108, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059762.1295145}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059762.229656, "x": -88.23575974822549, "y": 40.09273524466511, "z": 202.83408490297373, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.949566816221562, "steering_wheel_angle": -0.09, "front_wheel_angle": -0.0041380643941128885, "heading_rate": -0.01546933683269872, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059762.2294705}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.09, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059762.2294705}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059762.3297029, "x": -88.23575974822549, "y": 40.09273524466511, "z": 202.83408490297373, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.930318816221561, "steering_wheel_angle": -0.086, "front_wheel_angle": -0.003953942526841233, "heading_rate": -0.01465746489106557, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059762.3295107}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.49, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.086, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059762.3295107}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059762.4296997, "x": -88.23575974822549, "y": 40.09273524466511, "z": 202.83408490297373, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.968942816221562, "steering_wheel_angle": -0.087, "front_wheel_angle": -0.0039999711764795165, "heading_rate": -0.015078096764281715, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059762.4295063}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.087, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059762.4295063}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059762.5296817, "x": -88.23575974822549, "y": 40.09273524466511, "z": 202.83408490297373, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.930318816221561, "steering_wheel_angle": -0.088, "front_wheel_angle": -0.004046001037507012, "heading_rate": -0.014998734127374716, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059762.5295076}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.49, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.088, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059762.5295076}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059762.6299493, "x": -88.23581526586183, "y": 40.09273256152235, "z": 202.86060915805982, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.968942816221562, "steering_wheel_angle": -0.084, "front_wheel_angle": -0.0038618888613507667, "heading_rate": -0.014557583118459318, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059762.6295447}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.084, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059762.6295447}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059762.729787, "x": -88.23581526586183, "y": 40.09273256152235, "z": 202.86060915805982, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.968942816221562, "steering_wheel_angle": -0.083, "front_wheel_angle": -0.003815863845306958, "heading_rate": -0.014384087825387148, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059762.7295704}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.083, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059762.7295704}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059762.8296692, "x": -88.23581526586183, "y": 40.09273256152235, "z": 202.86060915805982, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.930318816221561, "steering_wheel_angle": -0.079, "front_wheel_angle": -0.003631775890244649, "heading_rate": -0.013463165910323349, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059762.8294947}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.49, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.079, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059762.8294947}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059762.9297202, "x": -88.23581526586183, "y": 40.09273256152235, "z": 202.86060915805982, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.911198816221562, "steering_wheel_angle": -0.076, "front_wheel_angle": -0.003493722635840881, "heading_rate": -0.012842212408667458, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059762.929544}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.076, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059762.929544}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059763.0297325, "x": -88.23581526586183, "y": 40.09273256152235, "z": 202.86060915805982, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.911198816221562, "steering_wheel_angle": -0.076, "front_wheel_angle": -0.003493722635840881, "heading_rate": -0.012842212408667458, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059763.0295453}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.076, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059763.0295453}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059763.129778, "x": -88.23587103027198, "y": 40.09273003152263, "z": 202.86676315361146, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.968942816221562, "steering_wheel_angle": -0.077, "front_wheel_angle": -0.0035397391768435885, "heading_rate": -0.013343213173064788, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059763.129555}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.077, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059763.129555}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059763.2298465, "x": -88.23587103027198, "y": 40.09273003152263, "z": 202.86676315361146, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.949566816221562, "steering_wheel_angle": -0.07, "front_wheel_angle": -0.0032176488035831207, "heading_rate": -0.012028517703020759, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059763.2295702}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.07, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059763.2295702}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059763.3297346, "x": -88.23587103027198, "y": 40.09273003152263, "z": 202.86676315361146, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.911198816221562, "steering_wheel_angle": -0.069, "front_wheel_angle": -0.0031716407329421357, "heading_rate": -0.011658296629364797, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059763.3295345}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.069, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059763.3295345}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059763.42969, "x": -88.23587103027198, "y": 40.09273003152263, "z": 202.86676315361146, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.911198816221562, "steering_wheel_angle": -0.07, "front_wheel_angle": -0.0032176488035831207, "heading_rate": -0.011827413958769626, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059763.4295216}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.07, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059763.4295216}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059763.5297015, "x": -88.23587103027198, "y": 40.09273003152263, "z": 202.86676315361146, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": -0.076, "front_wheel_angle": -0.003493722635840881, "heading_rate": -0.012733033132079425, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059763.5294855}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.076, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059763.5294855}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059763.629759, "x": -88.23592584277517, "y": 40.09272774455474, "z": 202.871494795518, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": -0.103, "front_wheel_angle": -0.004736594384715439, "heading_rate": -0.01726279535267894, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059763.6295578}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.103, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059763.6295578}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059763.7297199, "x": -88.23592584277517, "y": 40.09272774455474, "z": 202.871494795518, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.833681816221562, "steering_wheel_angle": -0.156, "front_wheel_angle": -0.0071788787542625635, "heading_rate": -0.0254630230063602, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059763.7295272}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.156, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059763.7295272}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059763.8297153, "x": -88.23592584277517, "y": 40.09272774455474, "z": 202.871494795518, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.852273816221562, "steering_wheel_angle": -0.242, "front_wheel_angle": -0.011149117230417551, "heading_rate": -0.039894588106988045, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059763.829502}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059763.829502}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059763.9297037, "x": -88.23592584277517, "y": 40.09272774455474, "z": 202.871494795518, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.796881816221561, "steering_wheel_angle": -0.354, "front_wheel_angle": -0.016333267821078794, "heading_rate": -0.05691629144740478, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059763.9295242}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.354, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059763.9295242}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059764.029725, "x": -88.23592584277517, "y": 40.09272774455474, "z": 202.871494795518, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.776406816221561, "steering_wheel_angle": -0.457, "front_wheel_angle": -0.02111453264700293, "heading_rate": -0.07283946674032879, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059764.0295389}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.457, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059764.0295389}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059764.1298642, "x": -88.23597861215663, "y": 40.092726037644255, "z": 202.8460125480805, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.704918816221562, "steering_wheel_angle": -0.511, "front_wheel_angle": -0.023626497085213333, "heading_rate": -0.07855426177867864, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059764.1295204}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.51, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.511, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059764.1295204}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059764.2297778, "x": -88.23597861215663, "y": 40.092726037644255, "z": 202.8460125480805, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.667773816221562, "steering_wheel_angle": -0.542, "front_wheel_angle": -0.025070200689389237, "heading_rate": -0.08169112859944573, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059764.2295458}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.542, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059764.2295458}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059764.32967, "x": -88.23597861215663, "y": 40.092726037644255, "z": 202.8460125480805, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": -0.624, "front_wheel_angle": -0.028894857802328377, "heading_rate": -0.09145058852112233, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059764.329498}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.624, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059764.329498}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059764.4298248, "x": -88.23597861215663, "y": 40.092726037644255, "z": 202.8460125480805, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.563942816221561, "steering_wheel_angle": -0.804, "front_wheel_angle": -0.03732034629217818, "heading_rate": -0.1144925034265147, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059764.4295776}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.804, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059764.4295776}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059764.5297196, "x": -88.23597861215663, "y": 40.092726037644255, "z": 202.8460125480805, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.496721816221561, "steering_wheel_angle": -1.126, "front_wheel_angle": -0.05249674238372768, "heading_rate": -0.15435099919263934, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059764.5295405}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.126, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059764.5295405}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059764.629734, "x": -88.23602611111333, "y": 40.09272605768761, "z": 202.8677216240114, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.464913816221562, "steering_wheel_angle": -1.609, "front_wheel_angle": -0.07551876316888662, "heading_rate": -0.2175301322653179, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059764.6295512}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.609, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059764.6295512}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059764.7296941, "x": -88.23602611111333, "y": 40.09272605768761, "z": 202.8677216240114, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": -2.172, "front_wheel_angle": -0.10275928448385288, "heading_rate": -0.2868094901397267, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059764.7295303}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.172, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059764.7295303}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059764.829621, "x": -88.23602611111333, "y": 40.09272605768761, "z": 202.8677216240114, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": -2.643, "front_wheel_angle": -0.12589874828322062, "heading_rate": -0.3436128290135639, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059764.8294895}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.643, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059764.8294895}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059764.9297018, "x": -88.23602611111333, "y": 40.09272605768761, "z": 202.8677216240114, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.340958816221562, "steering_wheel_angle": -3.024, "front_wheel_angle": -0.14486024253411917, "heading_rate": -0.38237064315124986, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059764.9295268}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.024, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059764.9295268}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059765.0296502, "x": -88.23602611111333, "y": 40.09272605768761, "z": 202.8677216240114, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.324461816221562, "steering_wheel_angle": -3.332, "front_wheel_angle": -0.16035370049248587, "heading_rate": -0.41825572068572126, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059765.0295177}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.332, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059765.0295177}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059765.1296554, "x": -88.2360671666301, "y": 40.09272959860318, "z": 202.89973918963486, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": -3.596, "front_wheel_angle": -0.17375478501424993, "heading_rate": -0.43744060562705, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059765.1295137}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.596, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059765.1295137}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059765.2297037, "x": -88.2360671666301, "y": 40.09272959860318, "z": 202.89973918963486, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.2531018162215615, "steering_wheel_angle": -3.808, "front_wheel_angle": -0.18459915589188533, "heading_rate": -0.45368337357987887, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059765.2295012}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.808, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059765.2295012}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059765.3297203, "x": -88.2360671666301, "y": 40.09272959860318, "z": 202.89973918963486, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.210126816221561, "steering_wheel_angle": -4.06, "front_wheel_angle": -0.1975879841121795, "heading_rate": -0.46687295693556424, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059765.329535}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.06, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059765.329535}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059765.429686, "x": -88.2360671666301, "y": 40.09272959860318, "z": 202.89973918963486, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.183278816221561, "steering_wheel_angle": -4.422, "front_wheel_angle": -0.2164386778018133, "heading_rate": -0.499031278439201, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059765.4295022}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.422, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059765.4295022}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059765.5296886, "x": -88.2360671666301, "y": 40.09272959860318, "z": 202.89973918963486, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": -4.974, "front_wheel_angle": -0.24563713155490138, "heading_rate": -0.5523228602697162, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059765.5295143}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.974, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059765.5295143}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059765.6296902, "x": -88.23610148029222, "y": 40.092738092013654, "z": 202.93938777601394, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.142353816221561, "steering_wheel_angle": -5.474, "front_wheel_angle": -0.27258199530506205, "heading_rate": -0.6071257057024242, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059765.6295242}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.474, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059765.6295242}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059765.7296894, "x": -88.23610148029222, "y": 40.092738092013654, "z": 202.93938777601394, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": -5.802, "front_wheel_angle": -0.2905274540506423, "heading_rate": -0.6306763380161167, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059765.7295234}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.802, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059765.7295234}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059765.8296406, "x": -88.23610148029222, "y": 40.092738092013654, "z": 202.93938777601394, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": -6.133, "front_wheel_angle": -0.30886310062081124, "heading_rate": -0.6618301126601314, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059765.8295074}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.133, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059765.8295074}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059765.9296243, "x": -88.23610148029222, "y": 40.092738092013654, "z": 202.93938777601394, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": -6.475, "front_wheel_angle": -0.32805589903027255, "heading_rate": -0.6846967668958368, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059765.9294848}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.475, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059765.9294848}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059766.029751, "x": -88.23610148029222, "y": 40.092738092013654, "z": 202.93938777601394, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": -6.81, "front_wheel_angle": -0.34710986858511494, "heading_rate": -0.7630805561446093, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059766.0295186}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.81, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059766.0295186}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059766.1296682, "x": -88.23612766756712, "y": 40.09275202232502, "z": 202.9485383670242, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": -7.205, "front_wheel_angle": -0.3699136806053126, "heading_rate": -0.7800718274988806, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059766.1294985}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.205, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059766.1294985}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059766.2296746, "x": -88.23612766756712, "y": 40.09275202232502, "z": 202.9485383670242, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": -7.649, "front_wheel_angle": -0.3960037146282988, "heading_rate": -0.8280151731610247, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059766.2295008}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.649, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059766.2295008}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059766.3298612, "x": -88.23612766756712, "y": 40.09275202232502, "z": 202.9485383670242, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": -7.99, "front_wheel_angle": -0.4163870496429845, "heading_rate": -0.8482140801035654, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059766.3295434}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.99, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059766.3295434}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059766.4296494, "x": -88.23612766756712, "y": 40.09275202232502, "z": 202.9485383670242, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": -8.265, "front_wheel_angle": -0.4330544886641791, "heading_rate": -0.8704678441421674, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059766.4295158}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.265, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059766.4295158}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059766.5296764, "x": -88.23612766756712, "y": 40.09275202232502, "z": 202.9485383670242, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": -8.519, "front_wheel_angle": -0.4486383365150114, "heading_rate": -0.8912991784029212, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059766.5295162}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.519, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059766.5295162}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059766.629527, "x": -88.23614496692542, "y": 40.09277082132124, "z": 202.94920747577407, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": -8.713, "front_wheel_angle": -0.46066753427980484, "heading_rate": -0.918894248251674, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059766.6293972}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.713, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059766.6293972}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059766.7296367, "x": -88.23614496692542, "y": 40.09277082132124, "z": 202.94920747577407, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": -8.948, "front_wheel_angle": -0.4753906723835672, "heading_rate": -0.9370353634468186, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059766.7294862}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.948, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059766.7294862}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059766.829679, "x": -88.23614496692542, "y": 40.09277082132124, "z": 202.94920747577407, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": -9.234, "front_wheel_angle": -0.493541223589308, "heading_rate": -0.9456072993023973, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059766.829518}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.234, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059766.829518}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059766.9297402, "x": -88.23614496692542, "y": 40.09277082132124, "z": 202.94920747577407, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": -9.382, "front_wheel_angle": -0.5030372978338866, "heading_rate": -0.9844366950607688, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059766.9295306}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.382, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059766.9295306}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059767.0296555, "x": -88.23614496692542, "y": 40.09277082132124, "z": 202.94920747577407, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": -9.501, "front_wheel_angle": -0.5107253018907255, "heading_rate": -1.002432003528718, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059767.0294921}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.501, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059767.0294921}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059767.1297088, "x": -88.2361515805312, "y": 40.092791605874574, "z": 202.94894484315873, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": -9.622, "front_wheel_angle": -0.5185916114590025, "heading_rate": -0.9831082757322772, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059767.1295247}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.622, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059767.1295247}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059767.2298229, "x": -88.2361515805312, "y": 40.092791605874574, "z": 202.94894484315873, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": -9.732, "front_wheel_angle": -0.5257865568295523, "heading_rate": -0.9996074729733833, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059767.229522}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.732, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059767.229522}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059767.329671, "x": -88.2361515805312, "y": 40.092791605874574, "z": 202.94894484315873, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9592068162215615, "steering_wheel_angle": -9.778, "front_wheel_angle": -0.5288078916130516, "heading_rate": -0.9883170399211381, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059767.3295226}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.778, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059767.3295226}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059767.429614, "x": -88.2361515805312, "y": 40.092791605874574, "z": 202.94894484315873, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9376068162215616, "steering_wheel_angle": -9.817, "front_wheel_angle": -0.531375311414861, "heading_rate": -0.9574156421596159, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059767.4294856}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.17, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.817, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059767.4294856}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059767.5296443, "x": -88.2361515805312, "y": 40.092791605874574, "z": 202.94894484315873, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9483428162215617, "steering_wheel_angle": -9.866, "front_wheel_angle": -0.5346087128905433, "heading_rate": -0.9830195174180079, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059767.5295098}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.25, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.866, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059767.5295098}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059767.6296709, "x": -88.236147400862, "y": 40.092811265819385, "z": 202.92203876930893, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9483428162215617, "steering_wheel_angle": -9.866, "front_wheel_angle": -0.5346087128905433, "heading_rate": -0.9830195174180079, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059767.6295125}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.25, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.866, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059767.6295125}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059767.7296658, "x": -88.236147400862, "y": 40.092811265819385, "z": 202.92203876930893, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": -9.922, "front_wheel_angle": -0.5383145682873226, "heading_rate": -1.0286685021508348, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059767.7294922}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.922, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059767.7294922}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059767.8297062, "x": -88.236147400862, "y": 40.092811265819385, "z": 202.92203876930893, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9592068162215615, "steering_wheel_angle": -9.938, "front_wheel_angle": -0.5393754625996476, "heading_rate": -1.0124436397063585, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059767.829526}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.938, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059767.829526}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059767.9298317, "x": -88.236147400862, "y": 40.092811265819385, "z": 202.92203876930893, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9551178162215614, "steering_wheel_angle": -9.938, "front_wheel_angle": -0.5393754625996476, "heading_rate": -1.0054290186460373, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059767.9295495}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.938, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059767.9295495}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059768.0296464, "x": -88.236147400862, "y": 40.092811265819385, "z": 202.92203876930893, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.934942816221562, "steering_wheel_angle": -9.938, "front_wheel_angle": -0.5393754625996476, "heading_rate": -0.9703559133444315, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059768.0295115}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.938, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059768.0295115}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059768.1297271, "x": -88.23613439222993, "y": 40.09282762531128, "z": 203.02375237408157, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": -9.922, "front_wheel_angle": -0.5383145682873226, "heading_rate": -1.049661736888607, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059768.1295023}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.922, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059768.1295023}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059768.22963, "x": -88.23613439222993, "y": 40.09282762531128, "z": 203.02375237408157, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9443018162215617, "steering_wheel_angle": -9.888, "front_wheel_angle": -0.5360632387533159, "heading_rate": -0.9793217046649444, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059768.2295094}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.888, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059768.2295094}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059768.3296204, "x": -88.23613439222993, "y": 40.09282762531128, "z": 203.02375237408157, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9925668162215615, "steering_wheel_angle": -9.797, "front_wheel_angle": -0.530058012556982, "heading_rate": -1.0460925357547686, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059768.3294902}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.797, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059768.3294902}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059768.4296403, "x": -88.23613439222993, "y": 40.09282762531128, "z": 203.02375237408157, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9743538162215617, "steering_wheel_angle": -9.683, "front_wheel_angle": -0.5225763391030929, "heading_rate": -0.9989788827898021, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059768.4295094}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.683, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059768.4295094}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059768.5296323, "x": -88.23613439222993, "y": 40.09282762531128, "z": 203.02375237408157, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9996618162215616, "steering_wheel_angle": -9.536, "front_wheel_angle": -0.5129955509735178, "heading_rate": -1.0165771007317803, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059768.5294983}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.536, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059768.5294983}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059768.6297429, "x": -88.23611364573694, "y": 40.0928391895038, "z": 203.1518353665548, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": -9.323, "front_wheel_angle": -0.49924307936674317, "heading_rate": -1.0096942013912213, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059768.6295063}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.323, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059768.6295063}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059768.7296762, "x": -88.23611364573694, "y": 40.0928391895038, "z": 203.1518353665548, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.021246816221561, "steering_wheel_angle": -8.913, "front_wheel_angle": -0.47318712972554966, "heading_rate": -0.9539663029940764, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059768.7294905}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.913, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059768.7294905}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059768.8298512, "x": -88.23611364573694, "y": 40.0928391895038, "z": 203.1518353665548, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": -8.159, "front_wheel_angle": -0.4266051415663446, "heading_rate": -0.8859559535108738, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059768.829563}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.159, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059768.829563}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059768.9296353, "x": -88.23611364573694, "y": 40.0928391895038, "z": 203.1518353665548, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": -7.319, "front_wheel_angle": -0.37656528516660276, "heading_rate": -0.7584329418977532, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059768.929488}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.319, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059768.929488}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059769.029632, "x": -88.23611364573694, "y": 40.0928391895038, "z": 203.1518353665548, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": -6.572, "front_wheel_angle": -0.33354671044612794, "heading_rate": -0.7078734035227672, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059769.0295124}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.572, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059769.0295124}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059769.129775, "x": -88.23608563955867, "y": 40.092845367122464, "z": 203.2403424937242, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": -5.944, "front_wheel_angle": -0.2983651935298736, "heading_rate": -0.6379175014459882, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059769.1295083}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.944, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059769.1295083}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059769.229842, "x": -88.23608563955867, "y": 40.092845367122464, "z": 203.2403424937242, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": -5.258, "front_wheel_angle": -0.2608821152723251, "heading_rate": -0.5714747445020574, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059769.2295606}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.258, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059769.2295606}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059769.32966, "x": -88.23608563955867, "y": 40.092845367122464, "z": 203.2403424937242, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": -4.592, "front_wheel_angle": -0.22537148206299096, "heading_rate": -0.5122669901074475, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059769.3294904}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.592, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059769.3294904}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059769.4297152, "x": -88.23608563955867, "y": 40.092845367122464, "z": 203.2403424937242, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.183278816221561, "steering_wheel_angle": -3.98, "front_wheel_angle": -0.19345282633439315, "heading_rate": -0.44460745115261613, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059769.4295216}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.98, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059769.4295216}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059769.5297234, "x": -88.23608563955867, "y": 40.092845367122464, "z": 203.2403424937242, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.210126816221561, "steering_wheel_angle": -3.423, "front_wheel_angle": -0.1649602412103384, "heading_rate": -0.3882202434194394, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059769.5295339}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.423, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059769.5295339}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059769.6298046, "x": -88.23605199283926, "y": 40.09284675391014, "z": 203.31238163301725, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.237486816221562, "steering_wheel_angle": -2.869, "front_wheel_angle": -0.13711940118999627, "heading_rate": -0.3304100515921442, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059769.62952}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.869, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059769.62952}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059769.7297935, "x": -88.23605199283926, "y": 40.09284675391014, "z": 203.31238163301725, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.2531018162215615, "steering_wheel_angle": -2.227, "front_wheel_angle": -0.10544458559202448, "heading_rate": -0.2571511489545795, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059769.7295501}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.227, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059769.7295501}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059769.8296564, "x": -88.23605199283926, "y": 40.09284675391014, "z": 203.31238163301725, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": -1.602, "front_wheel_angle": -0.07518285474514504, "heading_rate": -0.18772360432499718, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059769.8295143}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.602, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059769.8295143}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059769.9298222, "x": -88.23605199283926, "y": 40.09284675391014, "z": 203.31238163301725, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": -1.118, "front_wheel_angle": -0.052118048674829, "heading_rate": -0.13163584713043863, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059769.9295146}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.118, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059769.9295146}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059770.0297234, "x": -88.23605199283926, "y": 40.09284675391014, "z": 203.31238163301725, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.324461816221562, "steering_wheel_angle": -0.78, "front_wheel_angle": -0.0361945587175771, "heading_rate": -0.09363776018227202, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059770.0294988}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.78, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059770.0294988}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059770.1297975, "x": -88.23601453194637, "y": 40.092845619436424, "z": 203.37502247471775, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.355758816221561, "steering_wheel_angle": -0.571, "front_wheel_angle": -0.026421855002635993, "heading_rate": -0.07009615445097224, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059770.1295266}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.571, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059770.1295266}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059770.2296658, "x": -88.23601453194637, "y": 40.092845619436424, "z": 203.37502247471775, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": -0.266, "front_wheel_angle": -0.012258706907974296, "heading_rate": -0.0328990372352543, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059770.2294965}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.266, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059770.2294965}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059770.3298903, "x": -88.23601453194637, "y": 40.092845619436424, "z": 203.37502247471775, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": 0.141, "front_wheel_angle": 0.006487319683817855, "heading_rate": 0.0176123063717218, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059770.3295653}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.141, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059770.3295653}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059770.4296784, "x": -88.23601453194637, "y": 40.092845619436424, "z": 203.37502247471775, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": 0.545, "front_wheel_angle": 0.025209977961697393, "heading_rate": 0.07013010873512636, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059770.4294987}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.545, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059770.4294987}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059770.5295992, "x": -88.23601453194637, "y": 40.092845619436424, "z": 203.37502247471775, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": 0.83, "front_wheel_angle": 0.03854078372126814, "heading_rate": 0.10844965628517295, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059770.5294797}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.83, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059770.5294797}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059770.6296744, "x": -88.2359743430206, "y": 40.09284412382331, "z": 203.3855720894357, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.449201816221562, "steering_wheel_angle": 0.945, "front_wheel_angle": 0.04394932486586671, "heading_rate": 0.12506142347000707, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059770.6295178}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.945, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059770.6295178}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059770.7296195, "x": -88.2359743430206, "y": 40.09284412382331, "z": 203.3855720894357, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.480753816221561, "steering_wheel_angle": 0.936, "front_wheel_angle": 0.04352543053238867, "heading_rate": 0.12657572359436292, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059770.7294858}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.936, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059770.7294858}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059770.8296666, "x": -88.2359743430206, "y": 40.09284412382331, "z": 203.3855720894357, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.496721816221561, "steering_wheel_angle": 0.853, "front_wheel_angle": 0.03962112610077043, "heading_rate": 0.11644799896089275, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059770.8295052}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.853, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059770.8295052}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059770.9296587, "x": -88.2359743430206, "y": 40.09284412382331, "z": 203.3855720894357, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.514838816221562, "steering_wheel_angle": 0.756, "front_wheel_angle": 0.03506950889939869, "heading_rate": 0.10429235368168172, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059770.9294991}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.756, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059770.9294991}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059771.0296588, "x": -88.2359743430206, "y": 40.09284412382331, "z": 203.3855720894357, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.531078816221561, "steering_wheel_angle": 0.701, "front_wheel_angle": 0.032494044522278956, "heading_rate": 0.09764343187422185, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059771.0295153}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.701, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059771.0295153}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059771.1296482, "x": -88.23593138752307, "y": 40.09284426514806, "z": 203.4231810293368, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.547446816221561, "steering_wheel_angle": 0.606, "front_wheel_angle": 0.02805457246626904, "heading_rate": 0.08517235735912951, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059771.1295176}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059771.1295176}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059771.2295933, "x": -88.23593138752307, "y": 40.09284426514806, "z": 203.4231810293368, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.563942816221561, "steering_wheel_angle": 0.594, "front_wheel_angle": 0.02749460957940927, "heading_rate": 0.08433089380630816, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059771.2294822}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.594, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059771.2294822}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059771.3296144, "x": -88.23593138752307, "y": 40.09284426514806, "z": 203.4231810293368, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.580566816221562, "steering_wheel_angle": 0.569, "front_wheel_angle": 0.02632860349382649, "heading_rate": 0.08157581336272167, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059771.3295043}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.569, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059771.3295043}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059771.4296703, "x": -88.23593138752307, "y": 40.09284426514806, "z": 203.4231810293368, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": 0.513, "front_wheel_angle": 0.02371960288090329, "heading_rate": 0.0750643840820092, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059771.429512}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.513, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059771.429512}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059771.529713, "x": -88.23593138752307, "y": 40.09284426514806, "z": 203.4231810293368, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": 0.473, "front_wheel_angle": 0.021858438404162916, "heading_rate": 0.06917248228485685, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059771.5295172}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.473, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059771.5295172}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059771.6297653, "x": -88.23588603025578, "y": 40.09284689119255, "z": 203.4938409812461, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.633341816221561, "steering_wheel_angle": 0.438, "front_wheel_angle": 0.02023155937367406, "heading_rate": 0.06465497624055654, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059771.6295118}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.438, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059771.6295118}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059771.7296696, "x": -88.23588603025578, "y": 40.09284689119255, "z": 203.4938409812461, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.650493816221561, "steering_wheel_angle": 0.372, "front_wheel_angle": 0.01716787899885664, "heading_rate": 0.05539867735199739, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059771.7295196}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.26, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.372, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059771.7295196}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059771.8298097, "x": -88.23588603025578, "y": 40.09284689119255, "z": 203.4938409812461, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.667773816221562, "steering_wheel_angle": 0.284, "front_wheel_angle": 0.013091363545958393, "heading_rate": 0.04265164443019997, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059771.829491}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.284, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059771.829491}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059771.9296792, "x": -88.23588603025578, "y": 40.09284689119255, "z": 203.4938409812461, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.687366816221561, "steering_wheel_angle": 0.189, "front_wheel_angle": 0.008701273839504779, "heading_rate": 0.028653745988060204, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059771.929522}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.189, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059771.929522}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059772.029897, "x": -88.23588603025578, "y": 40.09284689119255, "z": 203.4938409812461, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.687366816221561, "steering_wheel_angle": 0.103, "front_wheel_angle": 0.004736594384715439, "heading_rate": 0.015597573936021805, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059772.029551}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.103, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059772.029551}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059772.12962, "x": -88.23588603025578, "y": 40.09284689119255, "z": 203.4938409812461, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.704918816221562, "steering_wheel_angle": 0.067, "front_wheel_angle": 0.0030796282205738327, "heading_rate": 0.01023739023805943, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059772.1295006}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.51, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.067, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059772.1295006}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059772.2296734, "x": -88.2358385001026, "y": 40.09285085876157, "z": 203.57013382003626, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.722598816221561, "steering_wheel_angle": 0.039, "front_wheel_angle": 0.0017919606816966718, "heading_rate": 0.006012874504689966, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059772.2294736}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.59, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.039, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059772.2294736}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059772.329749, "x": -88.2358385001026, "y": 40.09285085876157, "z": 203.57013382003626, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.740406816221562, "steering_wheel_angle": 0.017, "front_wheel_angle": 0.0007808857531862971, "heading_rate": 0.002644640959475904, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059772.3295228}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.017, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059772.3295228}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059772.4296532, "x": -88.2358385001026, "y": 40.09285085876157, "z": 203.57013382003626, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.758342816221561, "steering_wheel_angle": 0.005, "front_wheel_angle": 0.0002296361660609387, "heading_rate": 0.0007848892532625603, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059772.429504}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.75, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.005, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059772.429504}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059772.5298135, "x": -88.2358385001026, "y": 40.09285085876157, "z": 203.57013382003626, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.758342816221561, "steering_wheel_angle": 0.004, "front_wheel_angle": 0.00018370652604977013, "heading_rate": 0.0006279031722726857, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059772.529542}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.75, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.004, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059772.529542}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059772.6299424, "x": -88.23578881184359, "y": 40.09285513333011, "z": 203.56684209391423, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.776406816221561, "steering_wheel_angle": -0.005, "front_wheel_angle": -0.0002296361660609387, "heading_rate": -0.0007920653835781037, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059772.6295557}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.005, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059772.6295557}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059772.7296348, "x": -88.23578881184359, "y": 40.09285513333011, "z": 203.56684209391423, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.796881816221561, "steering_wheel_angle": -0.023, "front_wheel_angle": -0.001056575591671821, "heading_rate": -0.0036815069471841278, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059772.7295122}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.023, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059772.7295122}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059772.8296244, "x": -88.23578881184359, "y": 40.09285513333011, "z": 203.56684209391423, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.776406816221561, "steering_wheel_angle": -0.048, "front_wheel_angle": -0.0022057505363656986, "heading_rate": -0.007608128446558087, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059772.8295093}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.048, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059772.8295093}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059772.9296072, "x": -88.23578881184359, "y": 40.09285513333011, "z": 203.56684209391423, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.815217816221562, "steering_wheel_angle": -0.076, "front_wheel_angle": -0.003493722635840881, "heading_rate": -0.012282668616153786, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059772.9295065}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.076, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059772.9295065}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059773.0296013, "x": -88.23578881184359, "y": 40.09285513333011, "z": 203.56684209391423, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.815217816221562, "steering_wheel_angle": -0.083, "front_wheel_angle": -0.003815863845306958, "heading_rate": -0.013415211443366252, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059773.0295045}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.083, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059773.0295045}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059773.129862, "x": -88.23573737434512, "y": 40.092859457781245, "z": 203.54769503367922, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.833681816221562, "steering_wheel_angle": -0.079, "front_wheel_angle": -0.003631775890244649, "heading_rate": -0.012881511745599157, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059773.1295514}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.079, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059773.1295514}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059773.229629, "x": -88.23573737434512, "y": 40.092859457781245, "z": 203.54769503367922, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.815217816221562, "steering_wheel_angle": -0.078, "front_wheel_angle": -0.0035857569282793833, "heading_rate": -0.012606230729874253, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059773.2295105}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.078, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059773.2295105}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059773.3299096, "x": -88.23573737434512, "y": 40.092859457781245, "z": 203.54769503367922, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.852273816221562, "steering_wheel_angle": -0.077, "front_wheel_angle": -0.0035397391768435885, "heading_rate": -0.012665682141479114, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059773.329552}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.077, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059773.329552}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059773.4297574, "x": -88.23573737434512, "y": 40.092859457781245, "z": 203.54769503367922, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.870993816221562, "steering_wheel_angle": -0.078, "front_wheel_angle": -0.0035857569282793833, "heading_rate": -0.012942396882670897, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059773.429523}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.078, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059773.429523}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059773.5296543, "x": -88.23573737434512, "y": 40.092859457781245, "z": 203.54769503367922, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": -0.079, "front_wheel_angle": -0.003631775890244649, "heading_rate": -0.013236178919211469, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059773.529515}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.079, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059773.529515}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059773.6295962, "x": -88.23568452958297, "y": 40.09286359419988, "z": 203.54587059351528, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": -0.097, "front_wheel_angle": -0.0044603243150626555, "heading_rate": -0.016255899152480945, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059773.629478}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.097, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059773.629478}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059773.729623, "x": -88.23568452958297, "y": 40.09286359419988, "z": 203.54587059351528, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": -0.146, "front_wheel_angle": -0.006717808943590281, "heading_rate": -0.02448363293449168, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059773.7295043}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.146, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059773.7295043}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059773.829619, "x": -88.23568452958297, "y": 40.09286359419988, "z": 203.54587059351528, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": -0.213, "front_wheel_angle": -0.009809305375089042, "heading_rate": -0.03575146668582762, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059773.8295069}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059773.8295069}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059773.9296932, "x": -88.23568452958297, "y": 40.09286359419988, "z": 203.54587059351528, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.930318816221561, "steering_wheel_angle": -0.236, "front_wheel_angle": -0.010871830236794713, "heading_rate": -0.04030380237038665, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059773.929478}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.49, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.236, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059773.929478}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059774.0296917, "x": -88.23568452958297, "y": 40.09286359419988, "z": 203.54587059351528, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.930318816221561, "steering_wheel_angle": -0.238, "front_wheel_angle": -0.01096425433050356, "heading_rate": -0.040646462218943004, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059774.0295057}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.49, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.238, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059774.0295057}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059774.129656, "x": -88.2356303115183, "y": 40.092867360093045, "z": 203.5540777441317, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.949566816221562, "steering_wheel_angle": -0.226, "front_wheel_angle": -0.010409783299523325, "heading_rate": -0.03891610343153043, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059774.1295075}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.226, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059774.1295075}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059774.229691, "x": -88.2356303115183, "y": 40.092867360093045, "z": 203.5540777441317, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.930318816221561, "steering_wheel_angle": -0.209, "front_wheel_angle": -0.009624584547123486, "heading_rate": -0.0356797373938677, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059774.2294989}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.49, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.209, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059774.2294989}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059774.329762, "x": -88.2356303115183, "y": 40.092867360093045, "z": 203.5540777441317, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.968942816221562, "steering_wheel_angle": -0.176, "front_wheel_angle": -0.008101383877872934, "heading_rate": -0.03053908781689841, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059774.3296058}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.176, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059774.3296058}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059774.429735, "x": -88.2356303115183, "y": 40.092867360093045, "z": 203.5540777441317, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.949566816221562, "steering_wheel_angle": -0.148, "front_wheel_angle": -0.006810013166204691, "heading_rate": -0.02545813808393385, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059774.4295356}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.148, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059774.4295356}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059774.5295973, "x": -88.2356303115183, "y": 40.092867360093045, "z": 203.5540777441317, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.968942816221562, "steering_wheel_angle": -0.114, "front_wheel_angle": -0.005243202935496302, "heading_rate": -0.01976459843313509, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059774.5294995}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.114, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059774.5294995}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059774.6296284, "x": -88.23557461599175, "y": 40.09287017421723, "z": 203.54907876052428, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.990893816221561, "steering_wheel_angle": -0.065, "front_wheel_angle": -0.002987620546121671, "heading_rate": -0.011366996366727774, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059774.6295083}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.065, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059774.6295083}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059774.7296712, "x": -88.23557461599175, "y": 40.09287017421723, "z": 203.54907876052428, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.990893816221561, "steering_wheel_angle": -0.037, "front_wheel_angle": -0.0017000206580417147, "heading_rate": -0.006468053578437335, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059774.72951}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.037, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059774.72951}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059774.8298802, "x": -88.23557461599175, "y": 40.09287017421723, "z": 203.54907876052428, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.010541816221561, "steering_wheel_angle": -0.022, "front_wheel_angle": -0.0010106242725761874, "heading_rate": -0.0038766928654201532, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059774.8295388}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.022, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059774.8295388}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059774.9296236, "x": -88.23557461599175, "y": 40.09287017421723, "z": 203.54907876052428, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.010541816221561, "steering_wheel_angle": -0.022, "front_wheel_angle": -0.0010106242725761874, "heading_rate": -0.0038766928654201532, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059774.929504}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.022, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059774.929504}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059775.0296228, "x": -88.23557461599175, "y": 40.09287017421723, "z": 203.54907876052428, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.010541816221561, "steering_wheel_angle": -0.022, "front_wheel_angle": -0.0010106242725761874, "heading_rate": -0.0038766928654201532, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059775.0294797}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.022, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059775.0294797}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059775.129853, "x": -88.23551762823028, "y": 40.092872396647294, "z": 203.51309769674162, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.010541816221561, "steering_wheel_angle": -0.021, "front_wheel_angle": -0.0009646741586794069, "heading_rate": -0.003700430928428385, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059775.1295419}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.021, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059775.1295419}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059775.2298908, "x": -88.23551762823028, "y": 40.092872396647294, "z": 203.51309769674162, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.030317816221562, "steering_wheel_angle": -0.02, "front_wheel_angle": -0.0009187252498868106, "heading_rate": -0.0035528838019077704, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059775.229564}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.9, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059775.229564}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059775.3297, "x": -88.23551762823028, "y": 40.092872396647294, "z": 203.51309769674162, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.030317816221562, "steering_wheel_angle": -0.021, "front_wheel_angle": -0.0009646741586794069, "heading_rate": -0.0037305770052383927, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059775.3294802}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.9, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.021, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059775.3294802}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059775.429629, "x": -88.23551762823028, "y": 40.092872396647294, "z": 203.51309769674162, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.030317816221562, "steering_wheel_angle": -0.02, "front_wheel_angle": -0.0009187252498868106, "heading_rate": -0.0035528838019077704, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059775.4295084}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.9, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059775.4295084}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059775.5296125, "x": -88.23551762823028, "y": 40.092872396647294, "z": 203.51309769674162, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.070253816221562, "steering_wheel_angle": -0.02, "front_wheel_angle": -0.0009187252498868106, "heading_rate": -0.0036103041461810277, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059775.529478}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059775.529478}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059775.6298068, "x": -88.23545953559253, "y": 40.092874884378546, "z": 203.45027983269597, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.010541816221561, "steering_wheel_angle": -0.021, "front_wheel_angle": -0.0009646741586794069, "heading_rate": -0.003700430928428385, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059775.6295133}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.021, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059775.6295133}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059775.7296515, "x": -88.23545953559253, "y": 40.092874884378546, "z": 203.45027983269597, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.050221816221562, "steering_wheel_angle": -0.022, "front_wheel_angle": -0.0010106242725761874, "heading_rate": -0.003939856903960604, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059775.729495}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.022, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059775.729495}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059775.8296905, "x": -88.23545953559253, "y": 40.092874884378546, "z": 203.45027983269597, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.010541816221561, "steering_wheel_angle": -0.026, "front_wheel_angle": -0.001194436781101673, "heading_rate": -0.004581787018920856, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059775.8294897}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059775.8294897}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059775.9297628, "x": -88.23545953559253, "y": 40.092874884378546, "z": 203.45027983269597, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.990893816221561, "steering_wheel_angle": -0.042, "front_wheel_angle": -0.0019298797685140421, "heading_rate": -0.0073425985474497935, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059775.9294827}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.042, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059775.9294827}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059776.0295937, "x": -88.23545953559253, "y": 40.092874884378546, "z": 203.45027983269597, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.949566816221562, "steering_wheel_angle": -0.095, "front_wheel_angle": -0.004368243991637956, "heading_rate": -0.01632982847567396, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059776.0294793}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.095, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059776.0294793}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059776.1295996, "x": -88.23540147528203, "y": 40.09287751141613, "z": 203.2967380202262, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": -0.172, "front_wheel_angle": -0.007916843839452169, "heading_rate": -0.02885378759410737, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059776.1294713}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.172, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059776.1294713}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059776.2296226, "x": -88.23540147528203, "y": 40.09287751141613, "z": 203.2967380202262, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.968942816221562, "steering_wheel_angle": -0.229, "front_wheel_angle": -0.010548384515803491, "heading_rate": -0.039763939903811836, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059776.2294989}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059776.2294989}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059776.3296025, "x": -88.23540147528203, "y": 40.09287751141613, "z": 203.2967380202262, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.815217816221562, "steering_wheel_angle": -0.294, "front_wheel_angle": -0.013554122797411855, "heading_rate": -0.04765413124297101, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059776.3294709}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.294, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059776.3294709}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059776.4296327, "x": -88.23540147528203, "y": 40.09287751141613, "z": 203.2967380202262, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.870993816221562, "steering_wheel_angle": -0.387, "front_wheel_angle": -0.01786369498323308, "heading_rate": -0.06448363338447495, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059776.429476}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.387, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059776.429476}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059776.5296323, "x": -88.23540147528203, "y": 40.09287751141613, "z": 203.2967380202262, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.740406816221562, "steering_wheel_angle": -0.501, "front_wheel_angle": -0.023161043276796894, "heading_rate": -0.07845396849357225, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059776.52949}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.501, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059776.52949}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059776.6296227, "x": -88.2353471848621, "y": 40.09287937727305, "z": 203.12673162082928, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.722598816221561, "steering_wheel_angle": -0.66, "front_wheel_angle": -0.030576658291554273, "heading_rate": -0.10263100770933264, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059776.629482}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.59, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.66, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059776.629482}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059776.7296267, "x": -88.2353471848621, "y": 40.09287937727305, "z": 203.12673162082928, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.650493816221561, "steering_wheel_angle": -0.87, "front_wheel_angle": -0.04042007806052882, "heading_rate": -0.13048897940468965, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059776.7294803}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.26, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.87, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059776.7294803}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059776.829806, "x": -88.2353471848621, "y": 40.09287937727305, "z": 203.12673162082928, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": -1.088, "front_wheel_angle": -0.05069869757582344, "heading_rate": -0.1589657364578374, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059776.8295398}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.088, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059776.8295398}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059776.9296105, "x": -88.2353471848621, "y": 40.09287937727305, "z": 203.12673162082928, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.563942816221561, "steering_wheel_angle": -1.337, "front_wheel_angle": -0.06251541447825139, "heading_rate": -0.19194777815269307, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059776.9295032}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.337, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059776.9295032}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059777.0296485, "x": -88.2353471848621, "y": 40.09287937727305, "z": 203.12673162082928, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.496721816221561, "steering_wheel_angle": -1.645, "front_wheel_angle": -0.07724735581559365, "heading_rate": -0.22736653141879154, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059777.0295155}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.645, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059777.0295155}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059777.129601, "x": -88.2352996020176, "y": 40.092878841460184, "z": 203.09591532194605, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.449201816221562, "steering_wheel_angle": -1.996, "front_wheel_angle": -0.09419553300006986, "heading_rate": -0.26866361676079403, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059777.1294715}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.996, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059777.1294715}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059777.2296336, "x": -88.2352996020176, "y": 40.092878841460184, "z": 203.09591532194605, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.400926816221562, "steering_wheel_angle": -2.409, "front_wheel_angle": -0.11436186502609051, "heading_rate": -0.315424711598895, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059777.229513}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.409, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059777.229513}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059777.3296576, "x": -88.2352996020176, "y": 40.092878841460184, "z": 203.09591532194605, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": -2.832, "front_wheel_angle": -0.13527706374877735, "heading_rate": -0.3652594744350726, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059777.3295105}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.832, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059777.3295105}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059777.4296207, "x": -88.2352996020176, "y": 40.092878841460184, "z": 203.09591532194605, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.324461816221562, "steering_wheel_angle": -3.208, "front_wheel_angle": -0.15409801980552268, "heading_rate": -0.40167228954179274, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059777.4294798}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.208, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059777.4294798}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059777.5296319, "x": -88.2352996020176, "y": 40.092878841460184, "z": 203.09591532194605, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": -3.567, "front_wheel_angle": -0.1722771415020578, "heading_rate": -0.4390831285143305, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059777.5294836}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.567, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059777.5294836}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059777.6296341, "x": -88.23525894085114, "y": 40.09287433300352, "z": 203.0747117285106, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.267117816221561, "steering_wheel_angle": -3.943, "front_wheel_angle": -0.1915440195799151, "heading_rate": -0.4772285499667765, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059777.6294837}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.943, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059777.6294837}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059777.7296228, "x": -88.23525894085114, "y": 40.09287433300352, "z": 203.0747117285106, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.237486816221562, "steering_wheel_angle": -4.276, "front_wheel_angle": -0.20880822182112116, "heading_rate": -0.5073936049014862, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059777.7294815}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.276, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059777.7294815}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059777.829567, "x": -88.23525894085114, "y": 40.09287433300352, "z": 203.0747117285106, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.210126816221561, "steering_wheel_angle": -4.62, "front_wheel_angle": -0.2268477825633256, "heading_rate": -0.5382812530812497, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059777.8294697}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.62, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059777.8294697}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059777.9295752, "x": -88.23525894085114, "y": 40.09287433300352, "z": 203.0747117285106, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.183278816221561, "steering_wheel_angle": -4.953, "front_wheel_angle": -0.2445159790954515, "heading_rate": -0.5662672358503417, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059777.9294667}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.953, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059777.9294667}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059778.0295975, "x": -88.23525894085114, "y": 40.09287433300352, "z": 203.0747117285106, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": -5.305, "front_wheel_angle": -0.26342009985197085, "heading_rate": -0.6025819410781894, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059778.0294712}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059778.0294712}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059778.1296105, "x": -88.23522550393125, "y": 40.09286408871785, "z": 203.08663884659993, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.142353816221561, "steering_wheel_angle": -5.669, "front_wheel_angle": -0.2832243788342883, "heading_rate": -0.6321211179400219, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059778.1294785}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.669, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059778.1294785}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059778.2296033, "x": -88.23522550393125, "y": 40.09286408871785, "z": 203.08663884659993, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": -6.055, "front_wheel_angle": -0.3045214102918397, "heading_rate": -0.6727926176380422, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059778.2294772}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.055, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059778.2294772}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059778.3296163, "x": -88.23522550393125, "y": 40.09286408871785, "z": 203.08663884659993, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": -6.419, "front_wheel_angle": -0.32489555828710776, "heading_rate": -0.6986621316686101, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059778.3294716}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.419, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059778.3294716}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059778.429605, "x": -88.23522550393125, "y": 40.09286408871785, "z": 203.08663884659993, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": -6.745, "front_wheel_angle": -0.3433926905982658, "heading_rate": -0.7416549526412739, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059778.4294722}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.745, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059778.4294722}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059778.529586, "x": -88.23522550393125, "y": 40.09286408871785, "z": 203.08663884659993, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": -7.011, "front_wheel_angle": -0.3586672282667436, "heading_rate": -0.7541571807067736, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059778.5294728}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.011, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059778.5294728}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059778.6295798, "x": -88.23520014947432, "y": 40.092848313721134, "z": 203.02317332738687, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": -7.304, "front_wheel_angle": -0.3756882387072552, "heading_rate": -0.7811397861251622, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059778.6294672}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.304, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059778.6294672}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059778.7295902, "x": -88.23520014947432, "y": 40.092848313721134, "z": 203.02317332738687, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": -7.606, "front_wheel_angle": -0.3934550801594288, "heading_rate": -0.8091198206625217, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059778.7294679}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059778.7294679}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059778.8296573, "x": -88.23520014947432, "y": 40.092848313721134, "z": 203.02317332738687, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": -7.867, "front_wheel_angle": -0.40899905895659217, "heading_rate": -0.844872685925495, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059778.8294902}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.867, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059778.8294902}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059778.9296813, "x": -88.23520014947432, "y": 40.092848313721134, "z": 203.02317332738687, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": -7.867, "front_wheel_angle": -0.40899905895659217, "heading_rate": -0.8719627920874348, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059778.929476}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.867, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059778.929476}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059779.029615, "x": -88.23520014947432, "y": 40.092848313721134, "z": 203.02317332738687, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": -8.072, "front_wheel_angle": -0.42133514812767825, "heading_rate": -0.8595854822703827, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059779.0294797}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.072, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059779.0294797}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059779.1298118, "x": -88.23518448535634, "y": 40.09282873101224, "z": 202.9252447180719, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": -8.306, "front_wheel_angle": -0.435557515146887, "heading_rate": -0.8761945242096242, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059779.1295078}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.306, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059779.1295078}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059779.2296197, "x": -88.23518448535634, "y": 40.09282873101224, "z": 202.9252447180719, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": -8.4, "front_wheel_angle": -0.4413141901431105, "heading_rate": -0.8746540211187155, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059779.2294781}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.4, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059779.2294781}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059779.329566, "x": -88.23518448535634, "y": 40.09282873101224, "z": 202.9252447180719, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": -8.447, "front_wheel_angle": -0.44420202292796634, "heading_rate": -0.9276801169588648, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059779.3294635}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.447, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059779.3294635}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059779.4295967, "x": -88.23518448535634, "y": 40.09282873101224, "z": 202.9252447180719, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": -8.525, "front_wheel_angle": -0.4490087105978664, "heading_rate": -0.9241407351606407, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059779.4294684}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.525, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059779.4294684}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059779.5296335, "x": -88.23518448535634, "y": 40.09282873101224, "z": 202.9252447180719, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": -8.631, "front_wheel_angle": -0.4555694199063321, "heading_rate": -0.9224701784214989, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059779.5294797}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.631, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059779.5294797}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059779.6295977, "x": -88.23517940709561, "y": 40.09280698693726, "z": 202.86450523005877, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": -8.677, "front_wheel_angle": -0.4584268654136171, "heading_rate": -0.9291510277363034, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059779.6294708}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.677, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059779.6294708}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059779.7296622, "x": -88.23517940709561, "y": 40.09280698693726, "z": 202.86450523005877, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": -8.671, "front_wheel_angle": -0.4580537975465375, "heading_rate": -0.9610177948911975, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059779.7294807}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.671, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059779.7294807}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059779.829632, "x": -88.23517940709561, "y": 40.09280698693726, "z": 202.86450523005877, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": -8.66, "front_wheel_angle": -0.45737011879488554, "heading_rate": -0.97474233060365, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059779.829479}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.66, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059779.829479}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059779.929588, "x": -88.23517940709561, "y": 40.09280698693726, "z": 202.86450523005877, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": -8.627, "front_wheel_angle": -0.45532124374266364, "heading_rate": -0.8912886298772519, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059779.9294684}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.627, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059779.9294684}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059780.0298421, "x": -88.23517940709561, "y": 40.09280698693726, "z": 202.86450523005877, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": -8.544, "front_wheel_angle": -0.4501822565103845, "heading_rate": -0.9420181842100636, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059780.029513}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.544, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059780.029513}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059780.1296415, "x": -88.23518485376509, "y": 40.09278505993591, "z": 202.84279788591806, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": -8.443, "front_wheel_angle": -0.44395600189729123, "heading_rate": -0.8955077202259805, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059780.1294782}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.443, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059780.1294782}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059780.2295926, "x": -88.23518485376509, "y": 40.09278505993591, "z": 202.84279788591806, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": -8.393, "front_wheel_angle": -0.4408846311959622, "heading_rate": -0.9197616216610255, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059780.2294753}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.393, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059780.2294753}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059780.3296163, "x": -88.23518485376509, "y": 40.09278505993591, "z": 202.84279788591806, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": -8.35, "front_wheel_angle": -0.4382489910325875, "heading_rate": -0.9134881015093724, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059780.3294706}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.35, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059780.3294706}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059780.4296155, "x": -88.23518485376509, "y": 40.09278505993591, "z": 202.84279788591806, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": -8.356, "front_wheel_angle": -0.43861643749551765, "heading_rate": -0.883211187315896, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059780.429476}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.356, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059780.429476}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059780.5296233, "x": -88.23518485376509, "y": 40.09278505993591, "z": 202.84279788591806, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": -8.359, "front_wheel_angle": -0.4388001992540152, "heading_rate": -0.9294649514945387, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059780.5294766}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.359, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059780.5294766}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059780.6295984, "x": -88.23520068462872, "y": 40.09276562030123, "z": 202.7666870968913, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": -8.354, "front_wheel_angle": -0.43849394392844976, "heading_rate": -0.8994160626199607, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059780.62947}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.354, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059780.62947}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059780.7297626, "x": -88.23520068462872, "y": 40.09276562030123, "z": 202.7666870968913, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": -8.325, "front_wheel_angle": -0.4367190682233076, "heading_rate": -0.9390272526392183, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059780.7294965}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.325, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059780.7294965}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059780.8298726, "x": -88.23520068462872, "y": 40.09276562030123, "z": 202.7666870968913, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": -8.264, "front_wheel_angle": -0.4329934985322032, "heading_rate": -0.8865794169179678, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059780.8295016}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.264, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059780.8295016}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059780.9295905, "x": -88.23520068462872, "y": 40.09276562030123, "z": 202.7666870968913, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": -8.06, "front_wheel_angle": -0.42060988833244684, "heading_rate": -0.8858721130720557, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059780.9294686}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.06, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059780.9294686}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059781.0295718, "x": -88.23520068462872, "y": 40.09276562030123, "z": 202.7666870968913, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": -7.807, "front_wheel_angle": -0.4054098591870258, "heading_rate": -0.8365750476052715, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059781.0294645}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.807, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059781.0294645}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059781.1295826, "x": -88.23522501624282, "y": 40.092751781880295, "z": 202.75134045730096, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": -7.508, "front_wheel_angle": -0.38766434139006434, "heading_rate": -0.8214395309827619, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059781.1294653}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.508, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059781.1294653}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059781.2296298, "x": -88.23522501624282, "y": 40.092751781880295, "z": 202.75134045730096, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": -7.208, "front_wheel_angle": -0.3700883129379175, "heading_rate": -0.7562281917066591, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059781.2294729}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.208, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059781.2294729}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059781.3296256, "x": -88.23522501624282, "y": 40.092751781880295, "z": 202.75134045730096, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": -7.048, "front_wheel_angle": -0.3608051587676543, "heading_rate": -0.7472751494974501, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059781.3294787}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.048, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059781.3294787}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059781.4295847, "x": -88.23522501624282, "y": 40.092751781880295, "z": 202.75134045730096, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": -6.928, "front_wheel_angle": -0.35388321416260843, "heading_rate": -0.743200120784527, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059781.429468}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.928, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059781.429468}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059781.5295916, "x": -88.23522501624282, "y": 40.092751781880295, "z": 202.75134045730096, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": -6.817, "front_wheel_angle": -0.34751076644175677, "heading_rate": -0.7286649228473167, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059781.5294695}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.817, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059781.5294695}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059781.6295733, "x": -88.23525449648675, "y": 40.092745117831754, "z": 202.71102550431686, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": -6.619, "front_wheel_angle": -0.33621486022905317, "heading_rate": -0.703063070860785, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059781.6294682}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.619, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059781.6294682}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059781.729568, "x": -88.23525449648675, "y": 40.092745117831754, "z": 202.71102550431686, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": -6.293, "front_wheel_angle": -0.31781023632128563, "heading_rate": -0.6720568844471088, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059781.7294648}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.293, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059781.7294648}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059781.8295553, "x": -88.23525449648675, "y": 40.092745117831754, "z": 202.71102550431686, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": -5.854, "front_wheel_angle": -0.29339272798232574, "heading_rate": -0.6266451230316445, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059781.8294625}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.854, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059781.8294625}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059781.929632, "x": -88.23525449648675, "y": 40.092745117831754, "z": 202.71102550431686, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.142353816221561, "steering_wheel_angle": -5.245, "front_wheel_angle": -0.260180881346706, "heading_rate": -0.5781862089737316, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059781.929474}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.245, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059781.929474}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059782.0298405, "x": -88.23525449648675, "y": 40.092745117831754, "z": 202.71102550431686, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": -4.57, "front_wheel_angle": -0.22421253179743736, "heading_rate": -0.4881626822894088, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059782.0294995}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.57, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059782.0294995}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059782.129611, "x": -88.23525449648675, "y": 40.092745117831754, "z": 202.71102550431686, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": -3.986, "front_wheel_angle": -0.19376258275823838, "heading_rate": -0.4384389619554426, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059782.129468}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.986, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059782.129468}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059782.2295573, "x": -88.23528632569307, "y": 40.09274507669788, "z": 202.7541955853626, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1966388162215615, "steering_wheel_angle": -3.424, "front_wheel_angle": -0.16501093676761724, "heading_rate": -0.38313783495772413, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059782.229442}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.424, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059782.229442}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059782.329598, "x": -88.23528632569307, "y": 40.09274507669788, "z": 202.7541955853626, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1966388162215615, "steering_wheel_angle": -2.771, "front_wheel_angle": -0.13224426906389777, "heading_rate": -0.3060513493823041, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059782.3294683}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.771, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059782.3294683}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059782.4298437, "x": -88.23528632569307, "y": 40.09274507669788, "z": 202.7541955853626, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.237486816221562, "steering_wheel_angle": -2.007, "front_wheel_angle": -0.0947294717805623, "heading_rate": -0.2275136322545415, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059782.4295304}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.007, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059782.4295304}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059782.529599, "x": -88.23528632569307, "y": 40.09274507669788, "z": 202.7541955853626, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.267117816221561, "steering_wheel_angle": -1.296, "front_wheel_angle": -0.06056401578397651, "heading_rate": -0.14922675680691314, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059782.5294948}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.296, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059782.5294948}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059782.6296036, "x": -88.23532095035426, "y": 40.092749101280496, "z": 202.77033594994165, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": -0.738, "front_wheel_angle": -0.03422620481686899, "heading_rate": -0.08533144244475085, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059782.6294959}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.738, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059782.6294959}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059782.7296202, "x": -88.23532095035426, "y": 40.092749101280496, "z": 202.77033594994165, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3099338162215615, "steering_wheel_angle": -0.317, "front_wheel_angle": -0.014618936576890385, "heading_rate": -0.03734947526747068, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059782.7294722}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.54, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059782.7294722}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059782.8296037, "x": -88.23532095035426, "y": 40.092749101280496, "z": 202.77033594994165, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.324461816221562, "steering_wheel_angle": 0.218, "front_wheel_angle": 0.010040233940451006, "heading_rate": 0.02596428991589357, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059782.8294692}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.218, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059782.8294692}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059782.9296236, "x": -88.23532095035426, "y": 40.092749101280496, "z": 202.77033594994165, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.340958816221562, "steering_wheel_angle": 0.876, "front_wheel_angle": 0.04070215011110246, "heading_rate": 0.10674310363447188, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059782.9294708}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059782.9294708}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059783.0295985, "x": -88.23532095035426, "y": 40.092749101280496, "z": 202.77033594994165, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": 1.319, "front_wheel_angle": 0.061658425607857115, "heading_rate": 0.16567617259026035, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059783.0294673}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.319, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059783.0294673}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059783.1296067, "x": -88.23535876431369, "y": 40.09275362180345, "z": 202.8339472867557, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": 1.506, "front_wheel_angle": 0.07058287763787637, "heading_rate": 0.19194033537264424, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059783.1294763}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.506, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059783.1294763}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059783.2297053, "x": -88.23535876431369, "y": 40.09275362180345, "z": 202.8339472867557, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": 1.567, "front_wheel_angle": 0.0735043203929849, "heading_rate": 0.20480286613457463, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059783.2294805}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.567, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059783.2294805}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059783.329568, "x": -88.23535876431369, "y": 40.09275362180345, "z": 202.8339472867557, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": 1.571, "front_wheel_angle": 0.07369606797375743, "heading_rate": 0.20533906342898536, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059783.3294632}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.571, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059783.3294632}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059783.4295564, "x": -88.23535876431369, "y": 40.09275362180345, "z": 202.8339472867557, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.449201816221562, "steering_wheel_angle": 1.616, "front_wheel_angle": 0.07585473887123993, "heading_rate": 0.21612659935962242, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059783.4294617}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.616, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059783.4294617}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059783.5295708, "x": -88.23535876431369, "y": 40.09275362180345, "z": 202.8339472867557, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.464913816221562, "steering_wheel_angle": 1.649, "front_wheel_angle": 0.07743953174717741, "heading_rate": 0.2230847697688214, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059783.529464}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.649, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059783.529464}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059783.6295803, "x": -88.23539950643165, "y": 40.092755364391145, "z": 202.86876882338515, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.480753816221561, "steering_wheel_angle": 1.649, "front_wheel_angle": 0.07743953174717741, "heading_rate": 0.22550960422283037, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059783.6294663}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.649, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059783.6294663}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059783.7296193, "x": -88.23539950643165, "y": 40.092755364391145, "z": 202.86876882338515, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.496721816221561, "steering_wheel_angle": 1.629, "front_wheel_angle": 0.0764788723792937, "heading_rate": 0.22509572180760276, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059783.7294748}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.629, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059783.7294748}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059783.8295825, "x": -88.23539950643165, "y": 40.092755364391145, "z": 202.86876882338515, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.531078816221561, "steering_wheel_angle": 1.543, "front_wheel_angle": 0.07235429432714549, "heading_rate": 0.21772559121385338, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059783.829465}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.543, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059783.829465}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059783.9296067, "x": -88.23539950643165, "y": 40.092755364391145, "z": 202.86876882338515, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.531078816221561, "steering_wheel_angle": 1.358, "front_wheel_angle": 0.06351578425521909, "heading_rate": 0.19105244851164244, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059783.9294782}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.358, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059783.9294782}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059784.0295885, "x": -88.23539950643165, "y": 40.092755364391145, "z": 202.86876882338515, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.547446816221561, "steering_wheel_angle": 1.089, "front_wheel_angle": 0.05074599021193614, "heading_rate": 0.1541543558903637, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059784.0294678}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.089, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059784.0294678}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059784.1295798, "x": -88.23544297464895, "y": 40.09275280619166, "z": 202.83468865665233, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.580566816221562, "steering_wheel_angle": 0.757, "front_wheel_angle": 0.03511637126453862, "heading_rate": 0.10882318271778572, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059784.1294668}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.757, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059784.1294668}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059784.2295957, "x": -88.23544297464895, "y": 40.09275280619166, "z": 202.83468865665233, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": 0.393, "front_wheel_angle": 0.018142099519724435, "heading_rate": 0.056842032537289436, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059784.2294655}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.393, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059784.2294655}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059784.3295665, "x": -88.23544297464895, "y": 40.09275280619166, "z": 202.83468865665233, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": 0.073, "front_wheel_angle": 0.003355680274479731, "heading_rate": 0.010617621972063913, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059784.3294647}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.073, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059784.3294647}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059784.4296334, "x": -88.23544297464895, "y": 40.09275280619166, "z": 202.83468865665233, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.633341816221561, "steering_wheel_angle": -0.166, "front_wheel_angle": -0.007640070366829615, "heading_rate": -0.02441288734476471, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059784.4294682}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059784.4294682}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059784.5296202, "x": -88.23544297464895, "y": 40.09275280619166, "z": 202.83468865665233, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.650493816221561, "steering_wheel_angle": -0.275, "front_wheel_angle": -0.012674985428351849, "heading_rate": -0.040898822898240324, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059784.5294735}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.26, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.275, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059784.5294735}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059784.629628, "x": -88.23548952308153, "y": 40.092748610614066, "z": 202.77627024890987, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.667773816221562, "steering_wheel_angle": -0.232, "front_wheel_angle": -0.010686996757971879, "heading_rate": -0.03481755716212195, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059784.62949}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.232, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059784.62949}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059784.7298012, "x": -88.23548952308153, "y": 40.092748610614066, "z": 202.77627024890987, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.704918816221562, "steering_wheel_angle": -0.19, "front_wheel_angle": -0.008747427766931746, "heading_rate": -0.029079105087624145, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059784.7295036}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.51, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059784.7295036}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059784.8297083, "x": -88.23548952308153, "y": 40.092748610614066, "z": 202.77627024890987, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.704918816221562, "steering_wheel_angle": -0.186, "front_wheel_angle": -0.008562819384101573, "heading_rate": -0.0284653804645917, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059784.8294797}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.51, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.186, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059784.8294797}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059784.9295714, "x": -88.23548952308153, "y": 40.092748610614066, "z": 202.77627024890987, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.740406816221562, "steering_wheel_angle": -0.179, "front_wheel_angle": -0.008239801715843667, "heading_rate": -0.02790652253509351, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059784.9294715}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.179, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059784.9294715}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059785.029557, "x": -88.23548952308153, "y": 40.092748610614066, "z": 202.77627024890987, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.722598816221561, "steering_wheel_angle": -0.178, "front_wheel_angle": -0.008193661216406963, "heading_rate": -0.027494189446566338, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059785.0294597}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.59, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.178, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059785.0294597}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059785.1296115, "x": -88.23553904606513, "y": 40.09274501128413, "z": 202.7263250979817, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.740406816221562, "steering_wheel_angle": -0.176, "front_wheel_angle": -0.008101383877872934, "heading_rate": -0.02743770895051909, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059785.1294925}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.176, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059785.1294925}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059785.2296226, "x": -88.23553904606513, "y": 40.09274501128413, "z": 202.7263250979817, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.758342816221561, "steering_wheel_angle": -0.163, "front_wheel_angle": -0.007501700088116369, "heading_rate": -0.02564105746267094, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059785.2295086}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.75, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059785.2295086}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059785.3298657, "x": -88.23553904606513, "y": 40.09274501128413, "z": 202.7263250979817, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.776406816221561, "steering_wheel_angle": -0.123, "front_wheel_angle": -0.005657810092800902, "heading_rate": -0.01951523288930936, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059785.3295333}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.123, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059785.3295333}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059785.429611, "x": -88.23553904606513, "y": 40.09274501128413, "z": 202.7263250979817, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.776406816221561, "steering_wheel_angle": -0.08, "front_wheel_angle": -0.003677796062834341, "heading_rate": -0.012685580334486704, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059785.4294991}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.08, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059785.4294991}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059785.5298116, "x": -88.23553904606513, "y": 40.09274501128413, "z": 202.7263250979817, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.796881816221561, "steering_wheel_angle": -0.065, "front_wheel_angle": -0.002987620546121671, "heading_rate": -0.010410021313266092, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059785.5295398}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.065, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059785.5295398}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059785.6295962, "x": -88.23559048950035, "y": 40.09274205169706, "z": 202.74319127702788, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.815217816221562, "steering_wheel_angle": -0.064, "front_wheel_angle": -0.0029416185228755055, "heading_rate": -0.010341657448700768, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059785.6294925}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.064, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059785.6294925}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059785.729564, "x": -88.23559048950035, "y": 40.09274205169706, "z": 202.74319127702788, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.815217816221562, "steering_wheel_angle": -0.064, "front_wheel_angle": -0.0029416185228755055, "heading_rate": -0.010341657448700768, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059785.7294624}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.064, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059785.7294624}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059785.8295894, "x": -88.23559048950035, "y": 40.09274205169706, "z": 202.74319127702788, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.833681816221562, "steering_wheel_angle": -0.065, "front_wheel_angle": -0.002987620546121671, "heading_rate": -0.010596748152965933, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059785.8294902}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.065, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059785.8294902}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059785.9295933, "x": -88.23559048950035, "y": 40.09274205169706, "z": 202.74319127702788, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.852273816221562, "steering_wheel_angle": -0.066, "front_wheel_angle": -0.003033623778655747, "heading_rate": -0.010854718381222097, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059785.9294612}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.066, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059785.9294612}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059786.0296168, "x": -88.23559048950035, "y": 40.09274205169706, "z": 202.74319127702788, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.852273816221562, "steering_wheel_angle": -0.066, "front_wheel_angle": -0.003033623778655747, "heading_rate": -0.010854718381222097, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059786.0294607}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.066, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059786.0294607}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059786.1296213, "x": -88.23564339977742, "y": 40.09273943380719, "z": 202.74086386872546, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": -0.067, "front_wheel_angle": -0.0030796282205738327, "heading_rate": -0.011223836770986427, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059786.1294703}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.067, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059786.1294703}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059786.2295806, "x": -88.23564339977742, "y": 40.09273943380719, "z": 202.74086386872546, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": -0.065, "front_wheel_angle": -0.002987620546121671, "heading_rate": -0.010888508839996931, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059786.229462}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.065, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059786.229462}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059786.3296027, "x": -88.23564339977742, "y": 40.09273943380719, "z": 202.74086386872546, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": -0.052, "front_wheel_angle": -0.002389688533708352, "heading_rate": -0.00870931111736987, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059786.3294625}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.052, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059786.3294625}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059786.430075, "x": -88.23564339977742, "y": 40.09273943380719, "z": 202.74086386872546, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": -0.04, "front_wheel_angle": -0.0018379325036962971, "heading_rate": -0.006698409987514059, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059786.429532}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.04, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059786.429532}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059786.5295753, "x": -88.23564339977742, "y": 40.09273943380719, "z": 202.74086386872546, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.930318816221561, "steering_wheel_angle": -0.031, "front_wheel_angle": -0.0014242295429861569, "heading_rate": -0.005279666992834657, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059786.5294628}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.49, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.031, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059786.5294628}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059786.6295617, "x": -88.23569755335772, "y": 40.092736753737285, "z": 202.75890741079, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.930318816221561, "steering_wheel_angle": -0.027, "front_wheel_angle": -0.0012403929219419797, "heading_rate": -0.004598177682131102, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059786.6294594}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.49, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059786.6294594}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059786.7296228, "x": -88.23569755335772, "y": 40.092736753737285, "z": 202.75890741079, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.949566816221562, "steering_wheel_angle": -0.027, "front_wheel_angle": -0.0012403929219419797, "heading_rate": -0.0046369399808213535, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059786.7294867}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059786.7294867}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059786.8296053, "x": -88.23569755335772, "y": 40.092736753737285, "z": 202.75890741079, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.949566816221562, "steering_wheel_angle": -0.028, "front_wheel_angle": -0.0012863502684559124, "heading_rate": -0.004808741741838362, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059786.8294647}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.028, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059786.8294647}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059786.9296072, "x": -88.23569755335772, "y": 40.092736753737285, "z": 202.75890741079, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.968942816221562, "steering_wheel_angle": -0.028, "front_wheel_angle": -0.0012863502684559124, "heading_rate": -0.0048489402098997065, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059786.9294646}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.028, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059786.9294646}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059787.0295706, "x": -88.23569755335772, "y": 40.092736753737285, "z": 202.75890741079, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.968942816221562, "steering_wheel_angle": -0.049, "front_wheel_angle": -0.002251733223960032, "heading_rate": -0.008487993099949683, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059787.029461}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.049, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059787.029461}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059787.1300533, "x": -88.23575293738885, "y": 40.0927340397093, "z": 202.7846286495417, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.968942816221562, "steering_wheel_angle": -0.088, "front_wheel_angle": -0.004046001037507012, "heading_rate": -0.015251610572093363, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059787.1296127}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.088, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059787.1296127}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059787.2296839, "x": -88.23575293738885, "y": 40.0927340397093, "z": 202.7846286495417, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.990893816221561, "steering_wheel_angle": -0.154, "front_wheel_angle": -0.007086655051064875, "heading_rate": -0.026962959257157477, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059787.2294848}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.154, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059787.2294848}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059787.3295531, "x": -88.23575293738885, "y": 40.0927340397093, "z": 202.7846286495417, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.010541816221561, "steering_wheel_angle": -0.23, "front_wheel_angle": -0.010594587371297717, "heading_rate": -0.040641695618822284, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059787.3294568}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.23, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059787.3294568}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059787.42955, "x": -88.23575293738885, "y": 40.0927340397093, "z": 202.7846286495417, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.030317816221562, "steering_wheel_angle": -0.259, "front_wheel_angle": -0.011935003537068315, "heading_rate": -0.04615708811666612, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059787.429457}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.9, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059787.429457}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059787.529582, "x": -88.23575293738885, "y": 40.0927340397093, "z": 202.7846286495417, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.030317816221562, "steering_wheel_angle": -0.259, "front_wheel_angle": -0.011935003537068315, "heading_rate": -0.04615708811666612, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059787.5294585}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.9, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059787.5294585}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059787.629569, "x": -88.23580979283996, "y": 40.09273157490156, "z": 202.78185240481784, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.030317816221562, "steering_wheel_angle": -0.234, "front_wheel_angle": -0.010779411046211277, "heading_rate": -0.04168761830847628, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059787.6294568}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.9, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.234, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059787.6294568}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059787.7296402, "x": -88.23580979283996, "y": 40.09273157490156, "z": 202.78185240481784, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.030317816221562, "steering_wheel_angle": -0.195, "front_wheel_angle": -0.008978215725623, "heading_rate": -0.03472137657582625, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059787.7294698}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.9, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.195, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059787.7294698}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059787.8295877, "x": -88.23580979283996, "y": 40.09273157490156, "z": 202.78185240481784, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.050221816221562, "steering_wheel_angle": -0.157, "front_wheel_angle": -0.007224992432841391, "heading_rate": -0.02816667154403699, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059787.8294606}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.157, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059787.8294606}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059787.930271, "x": -88.23580979283996, "y": 40.09273157490156, "z": 202.78185240481784, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.050221816221562, "steering_wheel_angle": -0.152, "front_wheel_angle": -0.00699443621917048, "heading_rate": -0.02726781711626022, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059787.9295757}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059787.9295757}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059788.0298996, "x": -88.23580979283996, "y": 40.09273157490156, "z": 202.78185240481784, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.070253816221562, "steering_wheel_angle": -0.153, "front_wheel_angle": -0.007040545026252959, "heading_rate": -0.027667598938630848, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059788.0294914}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.153, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059788.0294914}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059788.1295812, "x": -88.23586785594587, "y": 40.09272987901536, "z": 202.76898021022964, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.090413816221561, "steering_wheel_angle": -0.149, "front_wheel_angle": -0.006856117103334404, "heading_rate": -0.027157076858600533, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059788.1294832}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.14, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.149, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059788.1294832}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059788.2295878, "x": -88.23586785594587, "y": 40.09272987901536, "z": 202.76898021022964, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.030317816221562, "steering_wheel_angle": -0.144, "front_wheel_angle": -0.006625609589192853, "heading_rate": -0.025622849520919515, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059788.2294893}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.9, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.144, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059788.2294893}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059788.32958, "x": -88.23586785594587, "y": 40.09272987901536, "z": 202.76898021022964, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.090413816221561, "steering_wheel_angle": -0.144, "front_wheel_angle": -0.006625609589192853, "heading_rate": -0.026244009509305444, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059788.3294802}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.14, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.144, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059788.3294802}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059788.4296153, "x": -88.23586785594587, "y": 40.09272987901536, "z": 202.76898021022964, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.030317816221562, "steering_wheel_angle": -0.144, "front_wheel_angle": -0.006625609589192853, "heading_rate": -0.025622849520919515, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059788.4295049}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.9, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.144, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059788.4295049}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059788.5295959, "x": -88.23586785594587, "y": 40.09272987901536, "z": 202.76898021022964, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.050221816221562, "steering_wheel_angle": -0.163, "front_wheel_angle": -0.007501700088116369, "heading_rate": -0.029245457540280687, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059788.5294805}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059788.5294805}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059788.62956, "x": -88.23592625374518, "y": 40.09272892203552, "z": 202.77274671379618, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.010541816221561, "steering_wheel_angle": -0.212, "front_wheel_angle": -0.009763123333029217, "heading_rate": -0.03745192087245734, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059788.6294584}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.212, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059788.6294584}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059788.729836, "x": -88.23592625374518, "y": 40.09272892203552, "z": 202.77274671379618, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.990893816221561, "steering_wheel_angle": -0.283, "front_wheel_angle": -0.013045094390063823, "heading_rate": -0.04963532314936754, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059788.7295437}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.283, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059788.7295437}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059788.829639, "x": -88.23592625374518, "y": 40.09272892203552, "z": 202.77274671379618, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.990893816221561, "steering_wheel_angle": -0.369, "front_wheel_angle": -0.017028749270248906, "heading_rate": -0.06479533269040806, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059788.8294656}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.369, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059788.8294656}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059788.9295626, "x": -88.23592625374518, "y": 40.09272892203552, "z": 202.77274671379618, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": -0.477, "front_wheel_angle": -0.02204446479807559, "heading_rate": -0.08035475762506371, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059788.9294598}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.477, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059788.9294598}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059789.0295784, "x": -88.23592625374518, "y": 40.09272892203552, "z": 202.77274671379618, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.870993816221562, "steering_wheel_angle": -0.588, "front_wheel_angle": -0.027214696270739868, "heading_rate": -0.09825230206825922, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059789.029481}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.588, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059789.029481}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059789.1295912, "x": -88.23598231092689, "y": 40.09272908723101, "z": 202.76969544147985, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.796881816221561, "steering_wheel_angle": -0.694, "front_wheel_angle": -0.032166534657962466, "heading_rate": -0.11211894116426105, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059789.129491}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.694, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059789.129491}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059789.2295988, "x": -88.23598231092689, "y": 40.09272908723101, "z": 202.76969544147985, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.740406816221562, "steering_wheel_angle": -0.804, "front_wheel_angle": -0.03732034629217818, "heading_rate": -0.1264522298990933, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059789.2294886}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.804, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059789.2294886}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059789.3295612, "x": -88.23598231092689, "y": 40.09272908723101, "z": 202.76969544147985, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.687366816221561, "steering_wheel_angle": -0.944, "front_wheel_angle": -0.04390222030354726, "heading_rate": -0.1446615919490023, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059789.3294582}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.944, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059789.3294582}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059789.42961, "x": -88.23598231092689, "y": 40.09272908723101, "z": 202.76969544147985, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.633341816221561, "steering_wheel_angle": -1.177, "front_wheel_angle": -0.05491290011400435, "heading_rate": -0.17564045527958216, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059789.4294925}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.177, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059789.4294925}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059789.5295966, "x": -88.23598231092689, "y": 40.09272908723101, "z": 202.76969544147985, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.580566816221562, "steering_wheel_angle": -1.549, "front_wheel_angle": -0.07264172705476721, "heading_rate": -0.2254157321597536, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059789.529486}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.549, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059789.529486}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059789.6298301, "x": -88.2360323952947, "y": 40.09273146514637, "z": 202.7936945642726, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.514838816221562, "steering_wheel_angle": -2.073, "front_wheel_angle": -0.09793672183529012, "heading_rate": -0.29206660140289986, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059789.6294866}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.073, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059789.6294866}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059789.729596, "x": -88.2360323952947, "y": 40.09273146514637, "z": 202.7936945642726, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.464913816221562, "steering_wheel_angle": -2.512, "front_wheel_angle": -0.11943002670619679, "heading_rate": -0.34500321004649404, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059789.7294953}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.512, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059789.7294953}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059789.829583, "x": -88.2360323952947, "y": 40.09273146514637, "z": 202.7936945642726, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": -2.82, "front_wheel_angle": -0.1346799993294532, "heading_rate": -0.3768600926071515, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059789.8294823}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.82, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059789.8294823}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059789.929582, "x": -88.2360323952947, "y": 40.09273146514637, "z": 202.7936945642726, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": -3.134, "front_wheel_angle": -0.15037642545638563, "heading_rate": -0.41135384088779636, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059789.9294827}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.134, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059789.9294827}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059790.0296586, "x": -88.2360323952947, "y": 40.09273146514637, "z": 202.7936945642726, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.324461816221562, "steering_wheel_angle": -3.562, "front_wheel_angle": -0.1720225149655828, "heading_rate": -0.4492798985360263, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059790.0294888}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.562, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059790.0294888}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059790.1296098, "x": -88.23607480458269, "y": 40.09273787606035, "z": 202.79362256633334, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.324461816221562, "steering_wheel_angle": -4.013, "front_wheel_angle": -0.19515724886475974, "heading_rate": -0.5111705259178048, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059790.1294649}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059790.1294649}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059790.2296903, "x": -88.23607480458269, "y": 40.09273787606035, "z": 202.79362256633334, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": -4.391, "front_wheel_angle": -0.21481534712992584, "heading_rate": -0.5437498609168904, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059790.229512}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.391, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059790.229512}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059790.3298097, "x": -88.23607480458269, "y": 40.09273787606035, "z": 202.79362256633334, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.2531018162215615, "steering_wheel_angle": -4.734, "front_wheel_angle": -0.23287323663045661, "heading_rate": -0.5762639692900863, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059790.3295324}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.734, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059790.3295324}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059790.42979, "x": -88.23607480458269, "y": 40.09273787606035, "z": 202.79362256633334, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.223742816221561, "steering_wheel_angle": -5.04, "front_wheel_angle": -0.24916619521176853, "heading_rate": -0.6013462292428469, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059790.4295003}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.04, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059790.4295003}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059790.5295537, "x": -88.23607480458269, "y": 40.09273787606035, "z": 202.79362256633334, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.183278816221561, "steering_wheel_angle": -5.394, "front_wheel_angle": -0.268237956474553, "heading_rate": -0.6238080146192728, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059790.5294576}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.394, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059790.5294576}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059790.629583, "x": -88.23610907898764, "y": 40.09275008213667, "z": 202.83086607901777, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": -5.839, "front_wheel_angle": -0.29256562973874756, "heading_rate": -0.6730139333672959, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059790.62949}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.839, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059790.62949}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059790.7295463, "x": -88.23610907898764, "y": 40.09275008213667, "z": 202.83086607901777, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": -6.313, "front_wheel_angle": -0.3189325532628558, "heading_rate": -0.7068454015500145, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059790.7294548}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.313, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059790.7294548}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059790.8295658, "x": -88.23610907898764, "y": 40.09275008213667, "z": 202.83086607901777, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": -6.667, "front_wheel_angle": -0.3389449755189879, "heading_rate": -0.7436607489361001, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059790.829456}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.667, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059790.829456}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059790.9296193, "x": -88.23610907898764, "y": 40.09275008213667, "z": 202.83086607901777, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": -6.957, "front_wheel_angle": -0.3555528756652151, "heading_rate": -0.758623990509717, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059790.9295192}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.957, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059790.9295192}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059791.0295815, "x": -88.23610907898764, "y": 40.09275008213667, "z": 202.83086607901777, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": -7.235, "front_wheel_angle": -0.37166099743298003, "heading_rate": -0.7719377408788464, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059791.0294607}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.235, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059791.0294607}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059791.129623, "x": -88.23613315351459, "y": 40.09276743752485, "z": 202.8950215173324, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": -7.498, "front_wheel_angle": -0.3870748300304181, "heading_rate": -0.7818399898234636, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059791.1295033}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.498, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059791.1295033}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059791.229731, "x": -88.23613315351459, "y": 40.09276743752485, "z": 202.8950215173324, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": -7.846, "front_wheel_angle": -0.40774174973459865, "heading_rate": -0.7997805503823742, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059791.229478}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.846, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059791.229478}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059791.3295972, "x": -88.23613315351459, "y": 40.09276743752485, "z": 202.8950215173324, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": -8.295, "front_wheel_angle": -0.43488550490275374, "heading_rate": -0.8311044013819527, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059791.3294876}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.295, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059791.3294876}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059791.429597, "x": -88.23613315351459, "y": 40.09276743752485, "z": 202.8950215173324, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": -8.764, "front_wheel_angle": -0.46384848189646516, "heading_rate": -0.9106133602202742, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059791.4294887}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059791.4294887}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059791.52957, "x": -88.23613315351459, "y": 40.09276743752485, "z": 202.8950215173324, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": -9.051, "front_wheel_angle": -0.4818975460255628, "heading_rate": -0.9357245584761285, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059791.5294566}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059791.5294566}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059791.6296465, "x": -88.23614614283737, "y": 40.09278706477569, "z": 202.93136865302128, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": -9.341, "front_wheel_angle": -0.5003994192198956, "heading_rate": -0.9419850052099823, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059791.6294942}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.341, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059791.6294942}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059791.729599, "x": -88.23614614283737, "y": 40.09278706477569, "z": 202.93136865302128, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": -9.644, "front_wheel_angle": -0.5200272416093256, "heading_rate": -0.9863895285393443, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059791.7294633}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.644, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059791.7294633}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059791.829593, "x": -88.23614614283737, "y": 40.09278706477569, "z": 202.93136865302128, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9592068162215615, "steering_wheel_angle": -9.779, "front_wheel_angle": -0.5288736556233344, "heading_rate": -0.9884662573862733, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059791.8294623}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.779, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059791.8294623}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059791.9296184, "x": -88.23614614283737, "y": 40.09278706477569, "z": 202.93136865302128, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9483428162215617, "steering_wheel_angle": -9.922, "front_wheel_angle": -0.5383145682873226, "heading_rate": -0.9913471959503509, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059791.9294963}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.25, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.922, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059791.9294963}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059792.0295868, "x": -88.23614614283737, "y": 40.09278706477569, "z": 202.93136865302128, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9592068162215615, "steering_wheel_angle": -10.093, "front_wheel_angle": -0.5497012966257416, "heading_rate": -1.0363149736916986, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059792.02946}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.093, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059792.02946}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059792.1295826, "x": -88.23614614283737, "y": 40.09278706477569, "z": 202.93136865302128, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9592068162215615, "steering_wheel_angle": -10.231, "front_wheel_angle": -0.5589697618521834, "heading_rate": -1.0580004396854648, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059792.1294572}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.231, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059792.1294572}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059792.2295878, "x": -88.2361478627142, "y": 40.09280694116544, "z": 202.93211445423105, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9483428162215617, "steering_wheel_angle": -10.317, "front_wheel_angle": -0.5647823281027424, "heading_rate": -1.0519276574666494, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059792.2294822}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.25, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059792.2294822}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059792.3296735, "x": -88.2361478627142, "y": 40.09280694116544, "z": 202.93211445423105, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9376068162215616, "steering_wheel_angle": -10.452, "front_wheel_angle": -0.5739645024328054, "heading_rate": -1.0532118697843371, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059792.3294694}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.17, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.452, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059792.3294694}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059792.4297101, "x": -88.2361478627142, "y": 40.09280694116544, "z": 202.93211445423105, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9376068162215616, "steering_wheel_angle": -10.588, "front_wheel_angle": -0.5832875744168757, "heading_rate": -1.0748783557865198, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059792.4295356}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.17, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.588, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059792.4295356}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059792.5296373, "x": -88.2361478627142, "y": 40.09280694116544, "z": 202.93211445423105, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9376068162215616, "steering_wheel_angle": -10.709, "front_wheel_angle": -0.5916452823371521, "heading_rate": -1.0945291322847355, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059792.5294938}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.17, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.709, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059792.5294938}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059792.629645, "x": -88.236139302985, "y": 40.092824759045676, "z": 202.93837675149294, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9100338162215618, "steering_wheel_angle": -10.777, "front_wheel_angle": -0.5963686825830284, "heading_rate": -1.0500482414671162, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059792.629528}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.96, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.777, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059792.629528}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059792.7296245, "x": -88.236139302985, "y": 40.092824759045676, "z": 202.93837675149294, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9113268162215618, "steering_wheel_angle": -10.847, "front_wheel_angle": -0.601251240556857, "heading_rate": -1.0637975683915488, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059792.7294524}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.847, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059792.7294524}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059792.829641, "x": -88.236139302985, "y": 40.092824759045676, "z": 202.93837675149294, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9243668162215615, "steering_wheel_angle": -10.87, "front_wheel_angle": -0.6028600337513604, "heading_rate": -1.0943589360940553, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059792.8294578}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.87, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059792.8294578}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059792.9295807, "x": -88.236139302985, "y": 40.092824759045676, "z": 202.93837675149294, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8908788162215617, "steering_wheel_angle": -10.876, "front_wheel_angle": -0.6032800891701446, "heading_rate": -1.0253706675278094, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059792.929483}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059792.929483}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059793.0295446, "x": -88.236139302985, "y": 40.092824759045676, "z": 202.93837675149294, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9100338162215618, "steering_wheel_angle": -10.876, "front_wheel_angle": -0.6032800891701446, "heading_rate": -1.0657395914462269, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059793.0294497}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.96, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059793.0294497}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059793.1294916, "x": -88.23612305029694, "y": 40.09283787305748, "z": 202.89930936554146, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8946738162215615, "steering_wheel_angle": -10.875, "front_wheel_angle": -0.603210069276537, "heading_rate": -1.0332895754309, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059793.12939}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.84, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.875, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059793.12939}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059793.2296479, "x": -88.23612305029694, "y": 40.09283787305748, "z": 202.89930936554146, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9035988162215616, "steering_wheel_angle": -10.875, "front_wheel_angle": -0.603210069276537, "heading_rate": -1.0521255833163594, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059793.2294562}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.875, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059793.2294562}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059793.3295825, "x": -88.23612305029694, "y": 40.09283787305748, "z": 202.89930936554146, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8984868162215616, "steering_wheel_angle": -10.869, "front_wheel_angle": -0.6027900394294491, "heading_rate": -1.0404261445798944, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059793.32947}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.869, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059793.32947}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059793.4295652, "x": -88.23612305029694, "y": 40.09283787305748, "z": 202.89930936554146, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9035988162215616, "steering_wheel_angle": -10.847, "front_wheel_angle": -0.601251240556857, "heading_rate": -1.047720023277319, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059793.4294536}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.847, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059793.4294536}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059793.5296352, "x": -88.23612305029694, "y": 40.09283787305748, "z": 202.89930936554146, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9165188162215614, "steering_wheel_angle": -10.791, "front_wheel_angle": -0.5973435438699869, "heading_rate": -1.0655385807274853, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059793.5294576}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.791, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059793.5294576}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059793.629732, "x": -88.23610180187426, "y": 40.09284534629573, "z": 202.8944038388814, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9087428162215616, "steering_wheel_angle": -10.729, "front_wheel_angle": -0.5930325210807877, "heading_rate": -1.039893987763189, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059793.6295238}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.729, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059793.6295238}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059793.7297418, "x": -88.23610180187426, "y": 40.09284534629573, "z": 202.8944038388814, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9256818162215614, "steering_wheel_angle": -10.626, "front_wheel_angle": -0.5859058624105714, "heading_rate": -1.0576798578374755, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059793.7294858}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.626, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059793.7294858}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059793.829578, "x": -88.23610180187426, "y": 40.09284534629573, "z": 202.8944038388814, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9269988162215617, "steering_wheel_angle": -10.4, "front_wheel_angle": -0.5704192227429441, "heading_rate": -1.0249926109092922, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059793.8294833}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.09, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.4, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059793.8294833}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059793.9296615, "x": -88.23610180187426, "y": 40.09284534629573, "z": 202.8944038388814, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9456468162215614, "steering_wheel_angle": -10.4, "front_wheel_angle": -0.5704192227429441, "heading_rate": -1.0600779325541092, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059793.9294875}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.4, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059793.9294875}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059794.0297756, "x": -88.23610180187426, "y": 40.09284534629573, "z": 202.8944038388814, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9524018162215615, "steering_wheel_angle": -10.084, "front_wheel_angle": -0.5490993100909504, "heading_rate": -1.022964537861865, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059794.0295358}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.703, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059794.0295358}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059794.1296, "x": -88.23607733758355, "y": 40.092846087550754, "z": 202.9127916966611, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9799218162215615, "steering_wheel_angle": -9.703, "front_wheel_angle": -0.5238856193294423, "heading_rate": -1.0110323840005482, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059794.1294794}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.703, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059794.1294794}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059794.2296188, "x": -88.23607733758355, "y": 40.092846087550754, "z": 202.9127916966611, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9743538162215617, "steering_wheel_angle": -9.154, "front_wheel_angle": -0.4884379013047299, "heading_rate": -0.9216179024929896, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059794.229458}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.154, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059794.229458}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059794.329603, "x": -88.23607733758355, "y": 40.092846087550754, "z": 202.9127916966611, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.001086816221561, "steering_wheel_angle": -8.336, "front_wheel_angle": -0.4373920150642976, "heading_rate": -0.8456955856190767, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059794.3294857}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.63, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.336, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059794.3294857}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059794.42962, "x": -88.23607733758355, "y": 40.092846087550754, "z": 202.9127916966611, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.035886816221562, "steering_wheel_angle": -7.483, "front_wheel_angle": -0.386191039734687, "heading_rate": -0.7735106767392351, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059794.4294877}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.483, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059794.4294877}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059794.529808, "x": -88.23607733758355, "y": 40.092846087550754, "z": 202.9127916966611, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": -6.69, "front_wheel_angle": -0.3402550254910502, "heading_rate": -0.6790066632312965, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059794.529502}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.69, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059794.529502}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059794.6295466, "x": -88.2360507363045, "y": 40.09283998857007, "z": 202.88621472409474, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": -6.019, "front_wheel_angle": -0.30252193651356296, "heading_rate": -0.6181076057104983, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059794.6294508}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.019, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059794.6294508}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059794.7296937, "x": -88.2360507363045, "y": 40.09283998857007, "z": 202.88621472409474, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": -5.394, "front_wheel_angle": -0.268237956474553, "heading_rate": -0.5701240202458414, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059794.7295034}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.394, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059794.7295034}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059794.8297071, "x": -88.2360507363045, "y": 40.09283998857007, "z": 202.88621472409474, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": -4.774, "front_wheel_angle": -0.23499309933644075, "heading_rate": -0.5050189845414319, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059794.8295999}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.774, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059794.8295999}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059794.9296687, "x": -88.2360507363045, "y": 40.09283998857007, "z": 202.88621472409474, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.142353816221561, "steering_wheel_angle": -4.23, "front_wheel_angle": -0.20641190484192629, "heading_rate": -0.45477801426099485, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059794.929519}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.23, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059794.929519}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059795.0296426, "x": -88.2360507363045, "y": 40.09283998857007, "z": 202.88621472409474, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": -3.708, "front_wheel_angle": -0.17947457426925031, "heading_rate": -0.40537540968050256, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059795.02946}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.708, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059795.02946}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059795.1296287, "x": -88.2360222726036, "y": 40.09282803439427, "z": 202.80291815452173, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1966388162215615, "steering_wheel_angle": -3.152, "front_wheel_angle": -0.15128088226045197, "heading_rate": -0.3507440067368268, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059795.129503}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059795.129503}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059795.2295623, "x": -88.2360222726036, "y": 40.09282803439427, "z": 202.80291815452173, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.223742816221561, "steering_wheel_angle": -2.581, "front_wheel_angle": -0.12283401645084008, "heading_rate": -0.29176018431346373, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059795.2294524}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.581, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059795.2294524}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059795.3295586, "x": -88.2360222726036, "y": 40.09282803439427, "z": 202.80291815452173, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.267117816221561, "steering_wheel_angle": -1.906, "front_wheel_angle": -0.0898333817167866, "heading_rate": -0.22167095644262144, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059795.3294506}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.906, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059795.3294506}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059795.4295962, "x": -88.2360222726036, "y": 40.09282803439427, "z": 202.80291815452173, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": -1.137, "front_wheel_angle": -0.05301758397784368, "heading_rate": -0.13391205261927655, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059795.4294848}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.137, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059795.4294848}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059795.5295918, "x": -88.2360222726036, "y": 40.09282803439427, "z": 202.80291815452173, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.324461816221562, "steering_wheel_angle": -0.516, "front_wheel_angle": -0.02385927097448736, "heading_rate": -0.061710293812935885, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059795.529453}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.516, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059795.529453}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059795.6295927, "x": -88.2359918901665, "y": 40.09281187186877, "z": 202.75417998295188, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.340958816221562, "steering_wheel_angle": -0.063, "front_wheel_angle": -0.002895617708822582, "heading_rate": -0.007589706691219133, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059795.6294856}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.063, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059795.6294856}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059795.7295892, "x": -88.2359918901665, "y": 40.09281187186877, "z": 202.75417998295188, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": 0.245, "front_wheel_angle": 0.01128777728186196, "heading_rate": 0.030293095163219298, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059795.72948}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.245, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059795.72948}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059795.8295975, "x": -88.2359918901665, "y": 40.09281187186877, "z": 202.75417998295188, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": 0.428, "front_wheel_angle": 0.019767017275988986, "heading_rate": 0.05367135391495059, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059795.829484}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.428, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059795.829484}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059795.929888, "x": -88.2359918901665, "y": 40.09281187186877, "z": 202.75417998295188, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.400926816221562, "steering_wheel_angle": 0.632, "front_wheel_angle": 0.02926844943723282, "heading_rate": 0.08039686449676697, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059795.9296904}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.632, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059795.9296904}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059796.0296082, "x": -88.2359918901665, "y": 40.09281187186877, "z": 202.75417998295188, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": 0.843, "front_wheel_angle": 0.03915132834423476, "heading_rate": 0.10894530239578502, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059796.029485}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.843, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059796.029485}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059796.129596, "x": -88.23595878195675, "y": 40.092794618815674, "z": 202.73514055522665, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.449201816221562, "steering_wheel_angle": 0.997, "front_wheel_angle": 0.04640055373989447, "heading_rate": 0.1320463540707247, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059796.1294873}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.997, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059796.1294873}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059796.22958, "x": -88.23595878195675, "y": 40.092794618815674, "z": 202.73514055522665, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.480753816221561, "steering_wheel_angle": 1.204, "front_wheel_angle": 0.05619343531607986, "heading_rate": 0.16348428585124825, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059796.2294748}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.204, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059796.2294748}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059796.329577, "x": -88.23595878195675, "y": 40.092794618815674, "z": 202.73514055522665, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.496721816221561, "steering_wheel_angle": 1.332, "front_wheel_angle": 0.06227731844077633, "heading_rate": 0.18317649868339184, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059796.3294528}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.332, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059796.3294528}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059796.429596, "x": -88.23595878195675, "y": 40.092794618815674, "z": 202.73514055522665, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.514838816221562, "steering_wheel_angle": 1.35, "front_wheel_angle": 0.06313462117723448, "heading_rate": 0.18792728409990944, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059796.4294558}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.35, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059796.4294558}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059796.5297277, "x": -88.23595878195675, "y": 40.092794618815674, "z": 202.73514055522665, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.547446816221561, "steering_wheel_angle": 1.391, "front_wheel_angle": 0.06508899179330882, "heading_rate": 0.19783471985228218, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059796.5294783}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.391, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059796.5294783}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059796.6296737, "x": -88.23592139749468, "y": 40.092778677618824, "z": 202.67653906452875, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.547446816221561, "steering_wheel_angle": 1.506, "front_wheel_angle": 0.07058287763787637, "heading_rate": 0.21458653321517204, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059796.6295114}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.506, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059796.6295114}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059796.729939, "x": -88.23592139749468, "y": 40.092778677618824, "z": 202.67653906452875, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.563942816221561, "steering_wheel_angle": 1.61, "front_wheel_angle": 0.07556675557775268, "heading_rate": 0.23216044451797188, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059796.7295556}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.61, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059796.7295556}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059796.8295636, "x": -88.23592139749468, "y": 40.092778677618824, "z": 202.67653906452875, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": 1.62, "front_wheel_angle": 0.07604675520915585, "heading_rate": 0.23870054656349818, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059796.829455}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.62, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059796.829455}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059796.9295583, "x": -88.23592139749468, "y": 40.092778677618824, "z": 202.67653906452875, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": 1.608, "front_wheel_angle": 0.07547077213305324, "heading_rate": 0.23688570335076334, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059796.929451}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.608, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059796.929451}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059797.0299041, "x": -88.23592139749468, "y": 40.092778677618824, "z": 202.67653906452875, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": 1.609, "front_wheel_angle": 0.07551876316888662, "heading_rate": 0.23940136838981993, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059797.0298033}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.609, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059797.0298033}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059797.1296701, "x": -88.23587977858466, "y": 40.09276523119858, "z": 202.65256806859892, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.650493816221561, "steering_wheel_angle": 1.608, "front_wheel_angle": 0.07547077213305324, "heading_rate": 0.24397455232884105, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059797.1295657}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.26, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.608, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059797.1295657}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059797.2296903, "x": -88.23587977858466, "y": 40.09276523119858, "z": 202.65256806859892, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.650493816221561, "steering_wheel_angle": 1.614, "front_wheel_angle": 0.07575873894590278, "heading_rate": 0.2449090280298786, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059797.2295601}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.26, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.614, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059797.2295601}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059797.3299584, "x": -88.23587977858466, "y": 40.09276523119858, "z": 202.65256806859892, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.667773816221562, "steering_wheel_angle": 1.628, "front_wheel_angle": 0.07643085386039222, "heading_rate": 0.24948338070095877, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059797.3298128}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.628, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059797.3298128}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059797.429559, "x": -88.23587977858466, "y": 40.09276523119858, "z": 202.65256806859892, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.687366816221561, "steering_wheel_angle": 1.644, "front_wheel_angle": 0.07719931527620957, "heading_rate": 0.25472115736221673, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059797.4294503}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.644, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059797.4294503}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059797.5300436, "x": -88.23587977858466, "y": 40.09276523119858, "z": 202.65256806859892, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.722598816221561, "steering_wheel_angle": 1.645, "front_wheel_angle": 0.07724735581559365, "heading_rate": 0.2597178862882206, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059797.5295475}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.59, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.645, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059797.5295475}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059797.629691, "x": -88.2358341011369, "y": 40.092755096051725, "z": 202.65490994892536, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.722598816221561, "steering_wheel_angle": 1.641, "front_wheel_angle": 0.07705520192059016, "heading_rate": 0.25906926675958697, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059797.6294672}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.59, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.641, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059797.6294672}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059797.729584, "x": -88.2358341011369, "y": 40.092755096051725, "z": 202.65490994892536, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.740406816221562, "steering_wheel_angle": 1.601, "front_wheel_angle": 0.07513487331724276, "heading_rate": 0.25494059929126905, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059797.7294528}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.601, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059797.7294528}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059797.829579, "x": -88.2358341011369, "y": 40.092755096051725, "z": 202.65490994892536, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.740406816221562, "steering_wheel_angle": 1.524, "front_wheel_angle": 0.0714444148263568, "heading_rate": 0.24237466436196742, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059797.8294778}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.524, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059797.8294778}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059797.9295568, "x": -88.2358341011369, "y": 40.092755096051725, "z": 202.65490994892536, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.758342816221561, "steering_wheel_angle": 1.383, "front_wheel_angle": 0.06470747352995232, "heading_rate": 0.22147732146880555, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059797.9294493}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.75, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.383, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059797.9294493}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059798.0297008, "x": -88.2358341011369, "y": 40.092755096051725, "z": 202.65490994892536, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.776406816221561, "steering_wheel_angle": 1.202, "front_wheel_angle": 0.05609854771725806, "heading_rate": 0.19369939898536911, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059798.0295384}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.202, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059798.0295384}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059798.1297648, "x": -88.23578521569517, "y": 40.09274889233739, "z": 202.64501066364136, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.796881816221561, "steering_wheel_angle": 0.993, "front_wheel_angle": 0.046211872687489615, "heading_rate": 0.161134212929667, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059798.1294737}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.993, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059798.1294737}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059798.2297473, "x": -88.23578521569517, "y": 40.09274889233739, "z": 202.64501066364136, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.796881816221561, "steering_wheel_angle": 0.724, "front_wheel_angle": 0.033570587593344664, "heading_rate": 0.11701647802848682, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059798.2296376}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.724, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059798.2296376}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059798.3297153, "x": -88.23578521569517, "y": 40.09274889233739, "z": 202.64501066364136, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.815217816221562, "steering_wheel_angle": 0.469, "front_wheel_angle": 0.021672431998539327, "heading_rate": 0.07620407499191437, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059798.3295033}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.469, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059798.3295033}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059798.4298456, "x": -88.23578521569517, "y": 40.09274889233739, "z": 202.64501066364136, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.815217816221562, "steering_wheel_angle": 0.295, "front_wheel_angle": 0.01360040549396957, "heading_rate": 0.04781687384655596, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059798.4294677}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.295, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059798.4294677}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059798.5297446, "x": -88.23578521569517, "y": 40.09274889233739, "z": 202.64501066364136, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.833681816221562, "steering_wheel_angle": 0.337, "front_wheel_angle": 0.015545392062093379, "heading_rate": 0.05514200439962072, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059798.5296369}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.337, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059798.5296369}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059798.6295648, "x": -88.23573377014641, "y": 40.09274577699987, "z": 202.65543477209943, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.833681816221562, "steering_wheel_angle": 0.436, "front_wheel_angle": 0.02013864099132237, "heading_rate": 0.07143890022977496, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059798.6294475}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.436, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059798.6294475}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059798.7297382, "x": -88.23573377014641, "y": 40.09274577699987, "z": 202.65543477209943, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.852273816221562, "steering_wheel_angle": 0.499, "front_wheel_angle": 0.023067967543457087, "heading_rate": 0.08255471519713711, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059798.7296135}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.499, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059798.7296135}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059798.8298132, "x": -88.23573377014641, "y": 40.09274577699987, "z": 202.65543477209943, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.870993816221562, "steering_wheel_angle": 0.518, "front_wheel_angle": 0.023952389304756717, "heading_rate": 0.08646969215548594, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059798.8296623}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.518, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059798.8296623}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059798.9302368, "x": -88.23573377014641, "y": 40.09274577699987, "z": 202.65543477209943, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": 0.528, "front_wheel_angle": 0.02441805620105836, "heading_rate": 0.0890100600885575, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059798.9299424}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059798.9299424}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059799.0295756, "x": -88.23573377014641, "y": 40.09274577699987, "z": 202.65543477209943, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.870993816221562, "steering_wheel_angle": 0.566, "front_wheel_angle": 0.026188735672827538, "heading_rate": 0.09454658372839574, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059799.0294597}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.566, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059799.0294597}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059799.129863, "x": -88.23568086852076, "y": 40.092744231955386, "z": 202.6936555041985, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.911198816221562, "steering_wheel_angle": 0.592, "front_wheel_angle": 0.027401300098077355, "heading_rate": 0.10074640090362516, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059799.1297283}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.592, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059799.1297283}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059799.2298362, "x": -88.23568086852076, "y": 40.092744231955386, "z": 202.6936555041985, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": 0.592, "front_wheel_angle": 0.027401300098077355, "heading_rate": 0.09988989590125638, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059799.2295446}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.592, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059799.2295446}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059799.330418, "x": -88.23568086852076, "y": 40.092744231955386, "z": 202.6936555041985, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.911198816221562, "steering_wheel_angle": 0.597, "front_wheel_angle": 0.02763458326328851, "heading_rate": 0.10160454844931145, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059799.3295348}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.597, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059799.3295348}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059799.4307218, "x": -88.23568086852076, "y": 40.092744231955386, "z": 202.6936555041985, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.930318816221561, "steering_wheel_angle": 0.614, "front_wheel_angle": 0.028427982068909004, "heading_rate": 0.10541181562594207, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059799.4295647}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.49, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.614, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059799.4295647}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059799.5299578, "x": -88.23568086852076, "y": 40.092744231955386, "z": 202.6936555041985, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.930318816221561, "steering_wheel_angle": 0.633, "front_wheel_angle": 0.029315154085035464, "heading_rate": 0.10870333316969169, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059799.5295048}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.49, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.633, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059799.5295048}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059799.629825, "x": -88.23562673921604, "y": 40.09274465283998, "z": 202.68324083733896, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.949566816221562, "steering_wheel_angle": 0.651, "front_wheel_angle": 0.030156054254560277, "heading_rate": 0.11276599693308371, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059799.6297116}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.651, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059799.6297116}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059799.7300513, "x": -88.23562673921604, "y": 40.09274465283998, "z": 202.68324083733896, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.968942816221562, "steering_wheel_angle": 0.659, "front_wheel_angle": 0.030529919437705017, "heading_rate": 0.11511925423369235, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059799.7299337}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.659, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059799.7299337}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059799.8296623, "x": -88.23562673921604, "y": 40.09274465283998, "z": 202.68324083733896, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.949566816221562, "steering_wheel_angle": 0.667, "front_wheel_angle": 0.030903865787646485, "heading_rate": 0.11556413416962609, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059799.8294897}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.667, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059799.8294897}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059799.929731, "x": -88.23562673921604, "y": 40.09274465283998, "z": 202.68324083733896, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.968942816221562, "steering_wheel_angle": 0.661, "front_wheel_angle": 0.03062339841373809, "heading_rate": 0.11547195580458205, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059799.9294715}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.661, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059799.9294715}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059800.0296793, "x": -88.23562673921604, "y": 40.09274465283998, "z": 202.68324083733896, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.949566816221562, "steering_wheel_angle": 0.635, "front_wheel_angle": 0.029408567177398832, "heading_rate": 0.10996919989091836, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059800.0294602}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.635, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059800.0294602}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059800.1296477, "x": -88.2355714528743, "y": 40.09274784593618, "z": 202.6509159716012, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.949566816221562, "steering_wheel_angle": 0.578, "front_wheel_angle": 0.02674827495362567, "heading_rate": 0.10001642879200175, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059800.1294622}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.578, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059800.1294622}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059800.2296085, "x": -88.2355714528743, "y": 40.09274784593618, "z": 202.6509159716012, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.949566816221562, "steering_wheel_angle": 0.496, "front_wheel_angle": 0.022928363332372515, "heading_rate": 0.08572769389601803, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059800.229481}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.496, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059800.229481}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059800.3296177, "x": -88.2355714528743, "y": 40.09274784593618, "z": 202.6509159716012, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.930318816221561, "steering_wheel_angle": 0.405, "front_wheel_angle": 0.018699042669962463, "heading_rate": 0.06932601575510676, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059800.3294857}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.49, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.405, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059800.3294857}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059800.429897, "x": -88.2355714528743, "y": 40.09274784593618, "z": 202.6509159716012, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.911198816221562, "steering_wheel_angle": 0.303, "front_wheel_angle": 0.01397071141081298, "heading_rate": 0.05135662037153334, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059800.4295108}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.303, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059800.4295108}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059800.5297008, "x": -88.2355714528743, "y": 40.09274784593618, "z": 202.6509159716012, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.949566816221562, "steering_wheel_angle": 0.186, "front_wheel_angle": 0.008562819384101573, "heading_rate": 0.03201100952363602, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059800.529497}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.186, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059800.529497}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059800.6299195, "x": -88.23551651513108, "y": 40.09275333390007, "z": 202.67376854866316, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.930318816221561, "steering_wheel_angle": 0.032, "front_wheel_angle": 0.0014701917131421402, "heading_rate": 0.005450050550804944, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059800.629768}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.49, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.032, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059800.629768}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059800.729692, "x": -88.23551651513108, "y": 40.09275333390007, "z": 202.67376854866316, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.911198816221562, "steering_wheel_angle": -0.129, "front_wheel_angle": -0.005934269527847416, "heading_rate": -0.021813332719713828, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059800.7294626}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.129, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059800.7294626}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059800.8295777, "x": -88.23551651513108, "y": 40.09275333390007, "z": 202.67376854866316, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": -0.293, "front_wheel_angle": -0.013507841332315113, "heading_rate": -0.04923274425676393, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059800.8294513}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.293, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059800.8294513}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059800.9295743, "x": -88.23551651513108, "y": 40.09275333390007, "z": 202.67376854866316, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": -0.481, "front_wheel_angle": -0.022230511186722545, "heading_rate": -0.08103314190477222, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059800.9294503}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.481, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059800.9294503}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059801.0296538, "x": -88.23551651513108, "y": 40.09275333390007, "z": 202.67376854866316, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": -0.688, "front_wheel_angle": -0.03188586152074161, "heading_rate": -0.1162484183214731, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059801.0294626}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.688, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059801.0294626}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059801.1296487, "x": -88.2354620101672, "y": 40.092759208319954, "z": 202.6956264924513, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.852273816221562, "steering_wheel_angle": -0.891, "front_wheel_angle": -0.04140753361535159, "heading_rate": -0.14824606767441972, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059801.1294897}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.891, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059801.1294897}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059801.2299984, "x": -88.2354620101672, "y": 40.092759208319954, "z": 202.6956264924513, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.852273816221562, "steering_wheel_angle": -1.103, "front_wheel_angle": -0.05140822513267024, "heading_rate": -0.18410727071124114, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059801.2294943}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.103, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059801.2294943}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059801.3296516, "x": -88.2354620101672, "y": 40.092759208319954, "z": 202.6956264924513, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.833681816221562, "steering_wheel_angle": -1.341, "front_wheel_angle": -0.06270591545619049, "heading_rate": -0.22270201089256256, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059801.3294652}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.341, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059801.3294652}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059801.429712, "x": -88.2354620101672, "y": 40.092759208319954, "z": 202.6956264924513, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.815217816221562, "steering_wheel_angle": -1.616, "front_wheel_angle": -0.07585473887123993, "heading_rate": -0.2671894772303024, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059801.4294827}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.616, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059801.4294827}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059801.5297792, "x": -88.2354620101672, "y": 40.092759208319954, "z": 202.6956264924513, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.796881816221561, "steering_wheel_angle": -1.887, "front_wheel_angle": -0.0889139449413724, "heading_rate": -0.31062853625490944, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059801.5294845}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.887, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059801.5294845}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059801.6302004, "x": -88.23540808490039, "y": 40.09276215888998, "z": 202.67431399141856, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.776406816221561, "steering_wheel_angle": -2.013, "front_wheel_angle": -0.09502078359144575, "heading_rate": -0.3287374490444767, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059801.6294708}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059801.6294708}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059801.7296317, "x": -88.23540808490039, "y": 40.09276215888998, "z": 202.67431399141856, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.740406816221562, "steering_wheel_angle": -1.866, "front_wheel_angle": -0.08789831602570912, "heading_rate": -0.2984559059537212, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059801.7294593}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.866, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059801.7294593}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059801.8297093, "x": -88.23540808490039, "y": 40.09276215888998, "z": 202.67431399141856, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.722598816221561, "steering_wheel_angle": -1.506, "front_wheel_angle": -0.07058287763787637, "heading_rate": -0.23723273105769985, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059801.829457}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.59, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.506, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059801.829457}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059801.9296439, "x": -88.23540808490039, "y": 40.09276215888998, "z": 202.67431399141856, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.687366816221561, "steering_wheel_angle": -1.035, "front_wheel_angle": -0.048194065264014, "heading_rate": -0.15882453544609737, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059801.9294884}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.035, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059801.9294884}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059802.029736, "x": -88.23540808490039, "y": 40.09276215888998, "z": 202.67431399141856, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.633341816221561, "steering_wheel_angle": -0.565, "front_wheel_angle": -0.02614211558334401, "heading_rate": -0.08355126282907524, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059802.0294864}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.565, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059802.0294864}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059802.1297977, "x": -88.23540808490039, "y": 40.09276215888998, "z": 202.67431399141856, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": -0.121, "front_wheel_angle": -0.005565666667536317, "heading_rate": -0.01761029902662357, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059802.1295137}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.121, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059802.1295137}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059802.2296634, "x": -88.23535809163066, "y": 40.09275951356318, "z": 202.65861539240197, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.563942816221561, "steering_wheel_angle": 0.255, "front_wheel_angle": 0.011750057201038522, "heading_rate": 0.036032107098125654, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059802.2294662}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.255, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059802.2294662}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059802.3297565, "x": -88.23535809163066, "y": 40.09275951356318, "z": 202.65861539240197, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.531078816221561, "steering_wheel_angle": 0.582, "front_wheel_angle": 0.026934828355777467, "heading_rate": 0.08092927117741473, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059802.329482}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.582, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059802.329482}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059802.4295862, "x": -88.23535809163066, "y": 40.09275951356318, "z": 202.65861539240197, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.480753816221561, "steering_wheel_angle": 0.932, "front_wheel_angle": 0.04333706678725195, "heading_rate": 0.12602725755186875, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059802.4294808}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.932, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059802.4294808}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059802.5296378, "x": -88.23535809163066, "y": 40.09275951356318, "z": 202.65861539240197, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.449201816221562, "steering_wheel_angle": 1.287, "front_wheel_angle": 0.060135961059043876, "heading_rate": 0.17121808295231633, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059802.5294616}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.287, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059802.5294616}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059802.629617, "x": -88.23531411531145, "y": 40.09275576518519, "z": 202.61822034313352, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": 1.692, "front_wheel_angle": 0.07950681679780082, "heading_rate": 0.22159545740416084, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059802.6294591}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.692, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059802.6294591}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059802.7296607, "x": -88.23531411531145, "y": 40.09275576518519, "z": 202.61822034313352, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": 2.235, "front_wheel_angle": 0.10583553953941618, "heading_rate": 0.28840458010201814, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059802.7294526}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.235, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059802.7294526}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059802.8299062, "x": -88.23531411531145, "y": 40.09275576518519, "z": 202.61822034313352, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.355758816221561, "steering_wheel_angle": 2.643, "front_wheel_angle": 0.12589874828322062, "heading_rate": 0.33570231784202864, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059802.8295012}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.643, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059802.8295012}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059802.929914, "x": -88.23531411531145, "y": 40.09275576518519, "z": 202.61822034313352, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.324461816221562, "steering_wheel_angle": 2.928, "front_wheel_angle": 0.14006153578841984, "heading_rate": 0.36457750207235623, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059802.9294758}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.928, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059802.9294758}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059803.0297303, "x": -88.23531411531145, "y": 40.09275576518519, "z": 202.61822034313352, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": 3.238, "front_wheel_angle": 0.15560924436798915, "heading_rate": 0.3958706074145754, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059803.0295055}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.238, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059803.0295055}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059803.1297145, "x": -88.23527603451716, "y": 40.092756343186416, "z": 202.65857525816205, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.267117816221561, "steering_wheel_angle": 3.558, "front_wheel_angle": 0.17181884325967295, "heading_rate": 0.4270461064684746, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059803.1295004}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.558, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059803.1295004}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059803.2297485, "x": -88.23527603451716, "y": 40.092756343186416, "z": 202.65857525816205, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.223742816221561, "steering_wheel_angle": 3.838, "front_wheel_angle": 0.1861397987175078, "heading_rate": 0.4450526737153167, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059803.229421}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.838, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059803.229421}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059803.329682, "x": -88.23527603451716, "y": 40.092756343186416, "z": 202.65857525816205, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.210126816221561, "steering_wheel_angle": 4.183, "front_wheel_angle": 0.20396732287079675, "heading_rate": 0.4823660355454615, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059803.3294988}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.183, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059803.3294988}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059803.4296384, "x": -88.23527603451716, "y": 40.092756343186416, "z": 202.65857525816205, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.183278816221561, "steering_wheel_angle": 4.47, "front_wheel_angle": 0.21895561126641144, "heading_rate": 0.5050230455584414, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059803.4294608}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.47, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059803.4294608}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059803.5295777, "x": -88.23527603451716, "y": 40.092756343186416, "z": 202.65857525816205, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": 4.737, "front_wheel_angle": 0.23303212377751606, "heading_rate": 0.5228984971417321, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059803.5294535}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.737, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059803.5294535}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059803.6297119, "x": -88.23524411310532, "y": 40.0927620938229, "z": 202.66065548546453, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": 4.966, "front_wheel_angle": 0.24520992755463675, "heading_rate": 0.5356822714885745, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059803.6295028}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.966, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059803.6295028}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059803.729725, "x": -88.23524411310532, "y": 40.0927620938229, "z": 202.66065548546453, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": 5.272, "front_wheel_angle": 0.261637659012641, "heading_rate": 0.5648397037384029, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059803.7295074}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.272, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059803.7295074}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059803.829631, "x": -88.23524411310532, "y": 40.0927620938229, "z": 202.66065548546453, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": 5.635, "front_wheel_angle": 0.2813632440053969, "heading_rate": 0.6096744971095545, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059803.8294568}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.635, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059803.8294568}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059803.929681, "x": -88.23524411310532, "y": 40.0927620938229, "z": 202.66065548546453, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": 5.955, "front_wheel_angle": 0.29897410552998716, "heading_rate": 0.650135836307804, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059803.9294963}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.955, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059803.9294963}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059804.0296104, "x": -88.23524411310532, "y": 40.0927620938229, "z": 202.66065548546453, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": 6.197, "front_wheel_angle": 0.31243528645838753, "heading_rate": 0.6599090956063162, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059804.029481}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.197, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059804.029481}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059804.1296294, "x": -88.23521897166856, "y": 40.09277265686851, "z": 202.65742760979418, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": 6.42, "front_wheel_angle": 0.3249519316110287, "heading_rate": 0.6672084969822931, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059804.1294541}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.42, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059804.1294541}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059804.229646, "x": -88.23521897166856, "y": 40.09277265686851, "z": 202.65742760979418, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": 6.569, "front_wheel_angle": 0.3333765732759744, "heading_rate": 0.6750183014300231, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059804.2294886}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.569, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059804.2294886}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059804.3295794, "x": -88.23521897166856, "y": 40.09277265686851, "z": 202.65742760979418, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": 6.672, "front_wheel_angle": 0.33922966572437063, "heading_rate": 0.6767943768871211, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059804.32945}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.672, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059804.32945}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059804.4297264, "x": -88.23521897166856, "y": 40.09277265686851, "z": 202.65742760979418, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": 6.797, "front_wheel_angle": 0.346365647132314, "heading_rate": 0.692224301904372, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059804.4294896}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.797, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059804.4294896}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059804.5296574, "x": -88.23521897166856, "y": 40.09277265686851, "z": 202.65742760979418, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": 6.934, "front_wheel_angle": 0.35422849785025884, "heading_rate": 0.709318276053148, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059804.5294547}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.934, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059804.5294547}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059804.629614, "x": -88.23520111254328, "y": 40.09278704231042, "z": 202.67858262619495, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": 7.094, "front_wheel_angle": 0.36346771340361284, "heading_rate": 0.7414186009102677, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059804.6294842}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.094, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059804.6294842}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059804.7296574, "x": -88.23520111254328, "y": 40.09278704231042, "z": 202.67858262619495, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": 7.321, "front_wheel_angle": 0.3766822669224759, "heading_rate": 0.7586924054055537, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059804.729498}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.321, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059804.729498}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059804.8295922, "x": -88.23520111254328, "y": 40.09278704231042, "z": 202.67858262619495, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": 7.443, "front_wheel_angle": 0.38383705468839474, "heading_rate": 0.760409139376613, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059804.8294578}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.443, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059804.8294578}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059804.9295874, "x": -88.23520111254328, "y": 40.09278704231042, "z": 202.67858262619495, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": 7.585, "front_wheel_angle": 0.3922121330680077, "heading_rate": 0.7658862033698637, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059804.929459}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.585, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059804.929459}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059805.0295339, "x": -88.23520111254328, "y": 40.09278704231042, "z": 202.67858262619495, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": 7.807, "front_wheel_angle": 0.4054098591870258, "heading_rate": 0.7544263956360163, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059805.0294428}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.807, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059805.0294428}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059805.1296318, "x": -88.23519140219489, "y": 40.092804256428046, "z": 202.66692622585467, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": 8.031, "front_wheel_angle": 0.4188588048890869, "heading_rate": 0.7964986089228083, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059805.1294878}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.031, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059805.1294878}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059805.2296767, "x": -88.23519140219489, "y": 40.092804256428046, "z": 202.66692622585467, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": 8.276, "front_wheel_angle": 0.4337255662112239, "heading_rate": 0.8285827184982963, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059805.229449}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.276, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059805.229449}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059805.329696, "x": -88.23519140219489, "y": 40.092804256428046, "z": 202.66692622585467, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": 8.47, "front_wheel_angle": 0.44561754229807116, "heading_rate": 0.8545660614787419, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059805.3295143}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.47, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059805.3295143}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059805.4297292, "x": -88.23519140219489, "y": 40.092804256428046, "z": 202.66692622585467, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9592068162215615, "steering_wheel_angle": 8.47, "front_wheel_angle": 0.44561754229807116, "heading_rate": 0.8079194424023914, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059805.4294927}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.47, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059805.4294927}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059805.529662, "x": -88.23519140219489, "y": 40.092804256428046, "z": 202.66692622585467, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": 8.656, "front_wheel_angle": 0.45712159776978295, "heading_rate": 0.8646133049066669, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059805.5294917}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.656, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059805.5294917}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059805.629589, "x": -88.23519022223313, "y": 40.09282160044705, "z": 202.67492214718152, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9592068162215615, "steering_wheel_angle": 8.778, "front_wheel_angle": 0.4647230571890348, "heading_rate": 0.8479781239327213, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059805.6294541}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.778, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059805.6294541}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059805.729584, "x": -88.23519022223313, "y": 40.09282160044705, "z": 202.67492214718152, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": 8.869, "front_wheel_angle": 0.4704223331170104, "heading_rate": 0.8759660840644181, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059805.7294772}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.869, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059805.7294772}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059805.82957, "x": -88.23519022223313, "y": 40.09282160044705, "z": 202.67492214718152, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9483428162215617, "steering_wheel_angle": 8.884, "front_wheel_angle": 0.47136420734022055, "heading_rate": 0.8461539180049351, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059805.8294566}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.25, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.884, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059805.8294566}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059805.9295986, "x": -88.23519022223313, "y": 40.09282160044705, "z": 202.67492214718152, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9592068162215615, "steering_wheel_angle": 8.881, "front_wheel_angle": 0.4711757771280562, "heading_rate": 0.861680053602167, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059805.9294798}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.881, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059805.9294798}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059806.0296216, "x": -88.23519022223313, "y": 40.09282160044705, "z": 202.67492214718152, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9592068162215615, "steering_wheel_angle": 8.875, "front_wheel_angle": 0.47079899977941525, "heading_rate": 0.8608775265474998, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059806.0294468}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.875, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059806.0294468}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059806.1295824, "x": -88.23519658448566, "y": 40.09283698638213, "z": 202.6794999061042, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9483428162215617, "steering_wheel_angle": 8.832, "front_wheel_angle": 0.46810199537047525, "heading_rate": 0.8393425416335565, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059806.1294541}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.25, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.832, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059806.1294541}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059806.2296102, "x": -88.23519658448566, "y": 40.09283698638213, "z": 202.6794999061042, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": 8.789, "front_wheel_angle": 0.46541064023620043, "heading_rate": 0.8651278494240381, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059806.2294793}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.789, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059806.2294793}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059806.329728, "x": -88.23519658448566, "y": 40.09283698638213, "z": 202.6794999061042, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9592068162215615, "steering_wheel_angle": 8.782, "front_wheel_angle": 0.4649730449186411, "heading_rate": 0.8485072982623375, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059806.329498}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.782, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059806.329498}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059806.4296248, "x": -88.23519658448566, "y": 40.09283698638213, "z": 202.6794999061042, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": 8.769, "front_wheel_angle": 0.46416076208658436, "heading_rate": 0.8624333916455384, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059806.4294724}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.769, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059806.4294724}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059806.5296204, "x": -88.23519658448566, "y": 40.09283698638213, "z": 202.6794999061042, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": 8.728, "front_wheel_angle": 0.46160229374552086, "heading_rate": 0.8744167340746251, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059806.529487}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.728, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059806.529487}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059806.6295674, "x": -88.23520947232223, "y": 40.09284981408633, "z": 202.69834753312986, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": 8.65, "front_wheel_angle": 0.45674890557215064, "heading_rate": 0.8791562752819339, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059806.6294723}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.65, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059806.6294723}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059806.7295556, "x": -88.23520947232223, "y": 40.09284981408633, "z": 202.69834753312986, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": 8.491, "front_wheel_angle": 0.44691131286639496, "heading_rate": 0.8574105656850625, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059806.7294457}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.491, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059806.7294457}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059806.8296497, "x": -88.23520947232223, "y": 40.09284981408633, "z": 202.69834753312986, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": 8.232, "front_wheel_angle": 0.43104330004996017, "heading_rate": 0.8515046522761657, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059806.8294532}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.232, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059806.8294532}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059806.9296324, "x": -88.23520947232223, "y": 40.09284981408633, "z": 202.69834753312986, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": 7.863, "front_wheel_angle": 0.40875948081754626, "heading_rate": 0.8020175171095367, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059806.929495}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.863, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059806.929495}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059807.0296226, "x": -88.23520947232223, "y": 40.09284981408633, "z": 202.69834753312986, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": 7.367, "front_wheel_angle": 0.3793755970001773, "heading_rate": 0.7506564210770451, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059807.029487}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059807.029487}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059807.1296253, "x": -88.2352287469455, "y": 40.092859575057695, "z": 202.6840244193249, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": 6.867, "front_wheel_angle": 0.35037765492176404, "heading_rate": 0.7009342034713469, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059807.1294851}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.867, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059807.1294851}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059807.2296994, "x": -88.2352287469455, "y": 40.092859575057695, "z": 202.6840244193249, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": 6.412, "front_wheel_angle": 0.3245010073116694, "heading_rate": 0.655701991913176, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059807.2294888}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.412, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059807.2294888}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059807.3296075, "x": -88.2352287469455, "y": 40.092859575057695, "z": 202.6840244193249, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": 6.138, "front_wheel_angle": 0.30914185937900573, "heading_rate": 0.6425058941578996, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059807.3294806}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.138, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059807.3294806}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059807.4295974, "x": -88.2352287469455, "y": 40.092859575057695, "z": 202.6840244193249, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": 6.013, "front_wheel_angle": 0.3021889587963148, "heading_rate": 0.636867511913026, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059807.4294786}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059807.4294786}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059807.5295877, "x": -88.2352287469455, "y": 40.092859575057695, "z": 202.6840244193249, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": 5.789, "front_wheel_angle": 0.2898120122835558, "heading_rate": 0.6383516498280453, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059807.5294757}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.789, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059807.5294757}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059807.629564, "x": -88.235254285344, "y": 40.09286616861527, "z": 202.6707461959726, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.142353816221561, "steering_wheel_angle": 5.236, "front_wheel_angle": 0.25969560460605984, "heading_rate": 0.5770576994990393, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059807.629446}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.236, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059807.629446}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059807.7295966, "x": -88.235254285344, "y": 40.09286616861527, "z": 202.6707461959726, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": 4.507, "front_wheel_angle": 0.2208985695644871, "heading_rate": 0.5017582089873722, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059807.7294512}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.507, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059807.7294512}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059807.829614, "x": -88.235254285344, "y": 40.09286616861527, "z": 202.6707461959726, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1966388162215615, "steering_wheel_angle": 3.805, "front_wheel_angle": 0.1844451748380467, "heading_rate": 0.429246736893319, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059807.829481}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.805, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059807.829481}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059807.9296203, "x": -88.235254285344, "y": 40.09286616861527, "z": 202.6707461959726, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.223742816221561, "steering_wheel_angle": 3.133, "front_wheel_angle": 0.15032619282248935, "heading_rate": 0.3579635597865581, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059807.9294808}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.133, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059807.9294808}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059808.0296125, "x": -88.235254285344, "y": 40.09286616861527, "z": 202.6707461959726, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.2531018162215615, "steering_wheel_angle": 2.45, "front_wheel_angle": 0.11637740829601881, "heading_rate": 0.28404423027761444, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059808.0294845}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.45, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059808.0294845}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059808.129588, "x": -88.23528630672511, "y": 40.0928696236583, "z": 202.65845644731297, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.267117816221561, "steering_wheel_angle": 1.751, "front_wheel_angle": 0.08234748718197514, "heading_rate": 0.2031113335945628, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059808.1294734}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.751, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059808.1294734}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059808.229579, "x": -88.23528630672511, "y": 40.0928696236583, "z": 202.65845644731297, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": 1.131, "front_wheel_angle": 0.05273346878379345, "heading_rate": 0.13319309748191493, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059808.229474}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.131, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059808.229474}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059808.3295674, "x": -88.23528630672511, "y": 40.0928696236583, "z": 202.65845644731297, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.324461816221562, "steering_wheel_angle": 0.684, "front_wheel_angle": 0.03169877152192992, "heading_rate": 0.08199850818727532, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059808.32947}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.684, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059808.32947}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059808.429598, "x": -88.23528630672511, "y": 40.0928696236583, "z": 202.65845644731297, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.355758816221561, "steering_wheel_angle": 0.411, "front_wheel_angle": 0.018977581326773664, "heading_rate": 0.050341112794273134, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059808.429481}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.411, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059808.429481}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059808.5296206, "x": -88.23528630672511, "y": 40.0928696236583, "z": 202.65845644731297, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": 0.368, "front_wheel_angle": 0.016982375171918963, "heading_rate": 0.045578177554101325, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059808.5294855}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.368, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059808.5294855}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059808.6295831, "x": -88.23532392879837, "y": 40.0928718475966, "z": 202.60574520964872, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": 0.425, "front_wheel_angle": 0.01962767892388535, "heading_rate": 0.053292925254140075, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059808.6294506}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.425, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059808.6294506}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059808.7295825, "x": -88.23532392879837, "y": 40.0928718475966, "z": 202.60574520964872, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": 0.535, "front_wheel_angle": 0.024744097684583643, "heading_rate": 0.06883357051060371, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059808.729451}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.535, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059808.729451}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059808.8296049, "x": -88.23532392879837, "y": 40.0928718475966, "z": 202.60574520964872, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": 0.554, "front_wheel_angle": 0.025629377643423473, "heading_rate": 0.07209841162114776, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059808.829476}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.554, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059808.829476}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059808.9295616, "x": -88.23532392879837, "y": 40.0928718475966, "z": 202.60574520964872, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.464913816221562, "steering_wheel_angle": 0.472, "front_wheel_angle": 0.021811934929106665, "heading_rate": 0.06271925968556555, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059808.929445}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.472, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059808.929445}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059809.0295684, "x": -88.23532392879837, "y": 40.0928718475966, "z": 202.60574520964872, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.464913816221562, "steering_wheel_angle": 0.401, "front_wheel_angle": 0.0185133750824784, "heading_rate": 0.053232035173403074, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059809.0294697}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.401, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059809.0294697}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059809.1295714, "x": -88.23536515653387, "y": 40.09287311207269, "z": 202.56982556815547, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.496721816221561, "steering_wheel_angle": 0.348, "front_wheel_angle": 0.01605515321523024, "heading_rate": 0.047166065272619115, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059809.129445}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.348, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059809.129445}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059809.2295873, "x": -88.23536515653387, "y": 40.09287311207269, "z": 202.56982556815547, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.514838816221562, "steering_wheel_angle": 0.327, "front_wheel_angle": 0.015082102583903858, "heading_rate": 0.044837306272043874, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059809.2294724}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059809.2294724}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059809.3296244, "x": -88.23536515653387, "y": 40.09287311207269, "z": 202.56982556815547, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.531078816221561, "steering_wheel_angle": 0.35, "front_wheel_angle": 0.016147853135638417, "heading_rate": 0.04851085348431956, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059809.329485}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.35, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059809.329485}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059809.4296134, "x": -88.23536515653387, "y": 40.09287311207269, "z": 202.56982556815547, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.531078816221561, "steering_wheel_angle": 0.343, "front_wheel_angle": 0.015823425056266507, "heading_rate": 0.04753605286048992, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059809.4294558}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.343, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059809.4294558}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059809.5296557, "x": -88.23536515653387, "y": 40.09287311207269, "z": 202.56982556815547, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.547446816221561, "steering_wheel_angle": 0.288, "front_wheel_angle": 0.013276452475300455, "heading_rate": 0.04029847546210924, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059809.5294907}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.288, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059809.5294907}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059809.629614, "x": -88.23540922558995, "y": 40.09287322650155, "z": 202.56098612173307, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.563942816221561, "steering_wheel_angle": 0.206, "front_wheel_angle": 0.009486056769587978, "heading_rate": 0.02908897629784523, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059809.6294587}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.206, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059809.6294587}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059809.7296414, "x": -88.23540922558995, "y": 40.09287322650155, "z": 202.56098612173307, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.580566816221562, "steering_wheel_angle": 0.16, "front_wheel_angle": 0.007363340777656139, "heading_rate": 0.022809510816949083, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059809.7294962}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.16, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059809.7294962}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059809.8296015, "x": -88.23540922558995, "y": 40.09287322650155, "z": 202.56098612173307, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": 0.147, "front_wheel_angle": 0.006763910446322207, "heading_rate": 0.021190386352918745, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059809.8294525}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.147, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059809.8294525}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059809.9296083, "x": -88.23540922558995, "y": 40.09287322650155, "z": 202.56098612173307, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.633341816221561, "steering_wheel_angle": 0.135, "front_wheel_angle": 0.00621077271792595, "heading_rate": 0.019845614873820586, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059809.9294832}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.135, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059809.9294832}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059810.029569, "x": -88.23540922558995, "y": 40.09287322650155, "z": 202.56098612173307, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.650493816221561, "steering_wheel_angle": 0.074, "front_wheel_angle": 0.0034016931847546217, "heading_rate": 0.010975818002087284, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059810.029443}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.26, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.074, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059810.029443}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059810.1296365, "x": -88.23545582755008, "y": 40.092873359913376, "z": 202.57616008712702, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.667773816221562, "steering_wheel_angle": 0.006, "front_wheel_angle": 0.00027556700966073483, "heading_rate": 0.0008977456713844534, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059810.129486}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.006, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059810.129486}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059810.2296517, "x": -88.23545582755008, "y": 40.092873359913376, "z": 202.57616008712702, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.687366816221561, "steering_wheel_angle": -0.015, "front_wheel_angle": -0.0006889987791691868, "heading_rate": -0.0022688518076148883, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059810.2295012}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059810.2295012}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059810.3296025, "x": -88.23545582755008, "y": 40.092873359913376, "z": 202.57616008712702, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.704918816221562, "steering_wheel_angle": -0.006, "front_wheel_angle": -0.00027556700966073483, "heading_rate": -0.0009160450435829375, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059810.329451}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.51, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.006, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059810.329451}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059810.4295957, "x": -88.23545582755008, "y": 40.092873359913376, "z": 202.57616008712702, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.722598816221561, "steering_wheel_angle": -0.005, "front_wheel_angle": -0.0002296361660609387, "heading_rate": -0.0007705369926314734, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059810.4294486}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.59, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.005, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059810.4294486}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059810.529589, "x": -88.23545582755008, "y": 40.092873359913376, "z": 202.57616008712702, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.740406816221562, "steering_wheel_angle": -0.005, "front_wheel_angle": -0.0002296361660609387, "heading_rate": -0.0007777131229470168, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059810.529476}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.005, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059810.529476}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059810.6295946, "x": -88.23550466358391, "y": 40.092873264838495, "z": 202.5866877231936, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.758342816221561, "steering_wheel_angle": -0.005, "front_wheel_angle": -0.0002296361660609387, "heading_rate": -0.0007848892532625603, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059810.6294804}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.75, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.005, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059810.6294804}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059810.7295487, "x": -88.23550466358391, "y": 40.092873264838495, "z": 202.5866877231936, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.740406816221562, "steering_wheel_angle": -0.021, "front_wheel_angle": -0.0009646741586794069, "heading_rate": -0.003267081074284532, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059810.7294424}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.021, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059810.7294424}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059810.8295841, "x": -88.23550466358391, "y": 40.092873264838495, "z": 202.5866877231936, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.758342816221561, "steering_wheel_angle": -0.051, "front_wheel_angle": -0.002343702222536118, "heading_rate": -0.008010715623399748, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059810.8294706}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.75, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059810.8294706}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059810.9295712, "x": -88.23550466358391, "y": 40.092873264838495, "z": 202.5866877231936, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.776406816221561, "steering_wheel_angle": -0.105, "front_wheel_angle": -0.004828694110281127, "heading_rate": -0.016655351710383248, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059810.9294462}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.105, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059810.9294462}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059811.0296428, "x": -88.23550466358391, "y": 40.092873264838495, "z": 202.5866877231936, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.815217816221562, "steering_wheel_angle": -0.134, "front_wheel_angle": -0.006164685813487009, "heading_rate": -0.021672998112588646, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059811.02946}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.134, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059811.02946}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059811.129602, "x": -88.23555583698135, "y": 40.09287316885754, "z": 202.59413728264775, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.815217816221562, "steering_wheel_angle": -0.122, "front_wheel_angle": -0.005611737772796137, "heading_rate": -0.019728972706898974, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059811.1294732}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.122, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059811.1294732}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059811.229588, "x": -88.23555583698135, "y": 40.09287316885754, "z": 202.59413728264775, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.815217816221562, "steering_wheel_angle": -0.09, "front_wheel_angle": -0.0041380643941128885, "heading_rate": -0.014547965673384377, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059811.2294757}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.09, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059811.2294757}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059811.3296125, "x": -88.23555583698135, "y": 40.09287316885754, "z": 202.59413728264775, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.852273816221562, "steering_wheel_angle": -0.07, "front_wheel_angle": -0.0032176488035831207, "heading_rate": -0.011513189358377236, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059811.3294444}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.07, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059811.3294444}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059811.4295328, "x": -88.23555583698135, "y": 40.09287316885754, "z": 202.59413728264775, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.852273816221562, "steering_wheel_angle": -0.062, "front_wheel_angle": -0.0028496181038668014, "heading_rate": -0.010196317377044658, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059811.4294367}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.062, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059811.4294367}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059811.5295887, "x": -88.23555583698135, "y": 40.09287316885754, "z": 202.59413728264775, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.852273816221562, "steering_wheel_angle": -0.043, "front_wheel_angle": -0.0019758552115223572, "heading_rate": -0.00706986612899228, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059811.5294673}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.043, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059811.5294673}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059811.6296575, "x": -88.23560873380153, "y": 40.09287334025007, "z": 202.5983134152982, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.870993816221562, "steering_wheel_angle": -0.016, "front_wheel_angle": -0.0007349416638626075, "heading_rate": -0.002652680545609742, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059811.6294746}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059811.6294746}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059811.7295964, "x": -88.23560873380153, "y": 40.09287334025007, "z": 202.5983134152982, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": 0.029, "front_wheel_angle": 0.0013323088207378546, "heading_rate": 0.00485564400482854, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059811.7294548}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.029, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059811.7294548}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059811.8295674, "x": -88.23560873380153, "y": 40.09287334025007, "z": 202.5983134152982, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.911198816221562, "steering_wheel_angle": 0.092, "front_wheel_angle": 0.004230132597423936, "heading_rate": 0.015549134832254521, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059811.829444}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059811.829444}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059811.929565, "x": -88.23560873380153, "y": 40.09287334025007, "z": 202.5983134152982, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": 0.201, "front_wheel_angle": 0.009255201596281284, "heading_rate": 0.03373183459053332, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059811.9294443}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.201, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059811.9294443}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059812.0295825, "x": -88.23560873380153, "y": 40.09287334025007, "z": 202.5983134152982, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.911198816221562, "steering_wheel_angle": 0.332, "front_wheel_angle": 0.015313731882929666, "heading_rate": 0.056294329126516586, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059812.0294468}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.332, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059812.0294468}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059812.1295805, "x": -88.23560873380153, "y": 40.09287334025007, "z": 202.5983134152982, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.911198816221562, "steering_wheel_angle": 0.456, "front_wheel_angle": 0.02106804914655314, "heading_rate": 0.07745299986517037, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059812.1294634}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059812.1294634}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059812.2295296, "x": -88.23566298104096, "y": 40.09287333588032, "z": 202.6023040157094, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.949566816221562, "steering_wheel_angle": 0.554, "front_wheel_angle": 0.025629377643423473, "heading_rate": 0.09583080544644222, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059812.2294354}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.554, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059812.2294354}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059812.3296132, "x": -88.23566298104096, "y": 40.09287333588032, "z": 202.6023040157094, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.968942816221562, "steering_wheel_angle": 0.601, "front_wheel_angle": 0.02782123250827102, "heading_rate": 0.104900071702176, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059812.3294973}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.601, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059812.3294973}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059812.4295855, "x": -88.23566298104096, "y": 40.09287333588032, "z": 202.6023040157094, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.968942816221562, "steering_wheel_angle": 0.625, "front_wheel_angle": 0.028941552329420327, "heading_rate": 0.10912655625459322, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059812.429472}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.625, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059812.429472}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059812.5297, "x": -88.23566298104096, "y": 40.09287333588032, "z": 202.6023040157094, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.949566816221562, "steering_wheel_angle": 0.63, "front_wheel_angle": 0.029175043937870793, "heading_rate": 0.10909547488887818, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059812.529518}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.63, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059812.529518}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059812.629855, "x": -88.23571800192707, "y": 40.09287175959022, "z": 202.57528268488448, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.968942816221562, "steering_wheel_angle": 0.624, "front_wheel_angle": 0.028894857802328377, "heading_rate": 0.10895039249738647, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059812.6294966}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.624, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059812.6294966}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059812.729686, "x": -88.23571800192707, "y": 40.09287175959022, "z": 202.57528268488448, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.010541816221561, "steering_wheel_angle": 0.596, "front_wheel_angle": 0.027587924106941566, "heading_rate": 0.10585240852034652, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059812.729491}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.596, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059812.729491}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059812.829581, "x": -88.23571800192707, "y": 40.09287175959022, "z": 202.57528268488448, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.010541816221561, "steering_wheel_angle": 0.526, "front_wheel_angle": 0.02432491278643489, "heading_rate": 0.09332725315608956, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059812.8294477}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.526, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059812.8294477}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059812.9295805, "x": -88.23571800192707, "y": 40.09287175959022, "z": 202.57528268488448, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.010541816221561, "steering_wheel_angle": 0.451, "front_wheel_angle": 0.020835650355672183, "heading_rate": 0.07993582023235703, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059812.9294727}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.451, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059812.9294727}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059813.0295608, "x": -88.23571800192707, "y": 40.09287175959022, "z": 202.57528268488448, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.030317816221562, "steering_wheel_angle": 0.373, "front_wheel_angle": 0.01721425805326267, "heading_rate": 0.06657733999809136, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059813.0294602}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.9, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.373, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059813.0294602}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059813.1295757, "x": -88.23577375928365, "y": 40.09286742552709, "z": 202.50990698108595, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.030317816221562, "steering_wheel_angle": 0.28, "front_wheel_angle": 0.012906294304269457, "heading_rate": 0.04991383145834531, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059813.1294386}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.9, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.28, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059813.1294386}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059813.2296019, "x": -88.23577375928365, "y": 40.09286742552709, "z": 202.50990698108595, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.050221816221562, "steering_wheel_angle": 0.189, "front_wheel_angle": 0.008701273839504779, "heading_rate": 0.03392222834648171, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059813.2294836}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.189, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059813.2294836}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059813.3295796, "x": -88.23577375928365, "y": 40.09286742552709, "z": 202.50990698108595, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.050221816221562, "steering_wheel_angle": 0.107, "front_wheel_angle": 0.0049207986882990285, "heading_rate": 0.019183580975403132, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059813.3294458}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.107, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059813.3294458}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059813.429595, "x": -88.23577375928365, "y": 40.09286742552709, "z": 202.50990698108595, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.070253816221562, "steering_wheel_angle": 0.021, "front_wheel_angle": 0.0009646741586794069, "heading_rate": 0.0037908691588584074, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059813.429476}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.021, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059813.429476}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059813.5295675, "x": -88.23577375928365, "y": 40.09286742552709, "z": 202.50990698108595, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.050221816221562, "steering_wheel_angle": -0.063, "front_wheel_angle": -0.002895617708822582, "heading_rate": -0.011288416211381066, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059813.5294552}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.063, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059813.5294552}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059813.6296012, "x": -88.23583081640581, "y": 40.092861236747765, "z": 202.4464614993398, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.090413816221561, "steering_wheel_angle": -0.092, "front_wheel_angle": -0.004230132597423936, "heading_rate": -0.01675539077567065, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059813.629491}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.14, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059813.629491}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059813.7295756, "x": -88.23583081640581, "y": 40.092861236747765, "z": 202.4464614993398, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.090413816221561, "steering_wheel_angle": -0.111, "front_wheel_angle": -0.005105022404758634, "heading_rate": -0.020220850341891135, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059813.7294707}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.14, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.111, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059813.7294707}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059813.8295708, "x": -88.23583081640581, "y": 40.092861236747765, "z": 202.4464614993398, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.070253816221562, "steering_wheel_angle": -0.162, "front_wheel_angle": -0.007455579099397041, "heading_rate": -0.02929863885556328, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059813.8294396}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.162, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059813.8294396}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059813.9297938, "x": -88.23583081640581, "y": 40.092861236747765, "z": 202.4464614993398, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.113246816221562, "steering_wheel_angle": -0.276, "front_wheel_angle": -0.012721244743952627, "heading_rate": -0.05083802901701129, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059813.929532}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.276, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059813.929532}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059814.029784, "x": -88.23583081640581, "y": 40.092861236747765, "z": 202.4464614993398, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.050221816221562, "steering_wheel_angle": -0.422, "front_wheel_angle": -0.019488351771840846, "heading_rate": -0.07598374104073213, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059814.0294833}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.422, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059814.0294833}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059814.1295588, "x": -88.23588908787708, "y": 40.092855099554974, "z": 202.44967666700185, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.050221816221562, "steering_wheel_angle": -0.507, "front_wheel_angle": -0.02344030053026761, "heading_rate": -0.09139728655428125, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059814.1294436}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.507, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059814.1294436}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059814.229669, "x": -88.23588908787708, "y": 40.092855099554974, "z": 202.44967666700185, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.010541816221561, "steering_wheel_angle": -0.494, "front_wheel_angle": -0.022835300116420734, "heading_rate": -0.08761001267731007, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059814.2294}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.494, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059814.2294}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059814.32958, "x": -88.23588908787708, "y": 40.092855099554974, "z": 202.44967666700185, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.050221816221562, "steering_wheel_angle": -0.433, "front_wheel_angle": -0.019999272759185574, "heading_rate": -0.07797631125977117, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059814.3294427}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.433, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059814.3294427}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059814.4297192, "x": -88.23588908787708, "y": 40.092855099554974, "z": 202.44967666700185, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.030317816221562, "steering_wheel_angle": -0.341, "front_wheel_angle": -0.015730742447424992, "heading_rate": -0.06083874895090862, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059814.4294124}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.9, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.341, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059814.4294124}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059814.5295708, "x": -88.23588908787708, "y": 40.092855099554974, "z": 202.44967666700185, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.968942816221562, "steering_wheel_angle": -0.181, "front_wheel_angle": -0.008332086375539805, "heading_rate": -0.03140878681134134, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059814.5294452}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.181, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059814.5294452}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059814.6295667, "x": -88.23594699236604, "y": 40.09285110437493, "z": 202.4420580722944, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.968942816221562, "steering_wheel_angle": -0.008, "front_wheel_angle": -0.00036743230800517036, "heading_rate": -0.00138504762961526, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059814.6294377}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.008, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059814.6294377}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059814.7295263, "x": -88.23594699236604, "y": 40.09285110437493, "z": 202.4420580722944, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.949566816221562, "steering_wheel_angle": 0.079, "front_wheel_angle": 0.003631775890244649, "heading_rate": 0.013576659405879288, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059814.7294319}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.079, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059814.7294319}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059814.8295643, "x": -88.23594699236604, "y": 40.09285110437493, "z": 202.4420580722944, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": 0.072, "front_wheel_angle": 0.0033096685742566774, "heading_rate": 0.012062234588915135, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059814.8294342}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.072, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059814.8294342}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059814.929782, "x": -88.23594699236604, "y": 40.09285110437493, "z": 202.4420580722944, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.815217816221562, "steering_wheel_angle": 0.035, "front_wheel_angle": 0.0016080854608783062, "heading_rate": 0.005653430321542836, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059814.929557}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.035, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059814.929557}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059815.0295882, "x": -88.23594699236604, "y": 40.09285110437493, "z": 202.4420580722944, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.796881816221561, "steering_wheel_angle": 0.182, "front_wheel_angle": 0.00837823053599315, "heading_rate": 0.029193580105703398, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059815.0294404}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.182, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059815.0294404}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059815.1295757, "x": -88.23600127745273, "y": 40.09284821705898, "z": 202.4036135426299, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.722598816221561, "steering_wheel_angle": 0.567, "front_wheel_angle": 0.026235357021001153, "heading_rate": 0.08805212347097223, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059815.1294544}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.59, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.567, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059815.1294544}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059815.22956, "x": -88.23600127745273, "y": 40.09284821705898, "z": 202.4036135426299, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.687366816221561, "steering_wheel_angle": 1.026, "front_wheel_angle": 0.04776911573848301, "heading_rate": 0.15742196334642844, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059815.2294364}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059815.2294364}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059815.329934, "x": -88.23600127745273, "y": 40.09284821705898, "z": 202.4036135426299, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": 1.481, "front_wheel_angle": 0.06938702959275601, "heading_rate": 0.21989791553822202, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059815.3295782}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.481, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059815.3295782}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059815.4297144, "x": -88.23600127745273, "y": 40.09284821705898, "z": 202.4036135426299, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.580566816221562, "steering_wheel_angle": 1.809, "front_wheel_angle": 0.08514472655295756, "heading_rate": 0.26438830867939894, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059815.4294913}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.809, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059815.4294913}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059815.5295637, "x": -88.23600127745273, "y": 40.09284821705898, "z": 202.4036135426299, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.514838816221562, "steering_wheel_angle": 1.986, "front_wheel_angle": 0.09371028320629529, "heading_rate": 0.2793867607761716, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059815.5294461}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.986, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059815.5294461}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059815.629602, "x": -88.23604815956926, "y": 40.09284356640447, "z": 202.37651345991043, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.480753816221561, "steering_wheel_angle": 2.098, "front_wheel_angle": 0.09915321348095764, "heading_rate": 0.2891121032769776, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059815.6294556}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.098, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059815.6294556}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059815.7296672, "x": -88.23604815956926, "y": 40.09284356640447, "z": 202.37651345991043, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": 2.388, "front_wheel_angle": 0.1133304730999011, "heading_rate": 0.31655680386355683, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059815.729484}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.388, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059815.729484}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059815.8297696, "x": -88.23604815956926, "y": 40.09284356640447, "z": 202.37651345991043, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": 2.765, "front_wheel_angle": 0.13194626789039948, "heading_rate": 0.36030689071381355, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059815.8294733}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.765, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059815.8294733}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059815.9296083, "x": -88.23604815956926, "y": 40.09284356640447, "z": 202.37651345991043, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3099338162215615, "steering_wheel_angle": 2.765, "front_wheel_angle": 0.13194626789039948, "heading_rate": 0.33905137629760296, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059815.9294503}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.54, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.765, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059815.9294503}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059816.0295596, "x": -88.23604815956926, "y": 40.09284356640447, "z": 202.37651345991043, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": 3.119, "front_wheel_angle": 0.14962310119424355, "heading_rate": 0.3804075271593132, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059816.0294383}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.119, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059816.0294383}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059816.1295807, "x": -88.23608590889674, "y": 40.09283585667525, "z": 202.41153126679097, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.267117816221561, "steering_wheel_angle": 3.487, "front_wheel_angle": 0.16820802624476353, "heading_rate": 0.4178982231556642, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059816.1294415}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.487, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059816.1294415}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059816.229556, "x": -88.23608590889674, "y": 40.09283585667525, "z": 202.41153126679097, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.223742816221561, "steering_wheel_angle": 3.782, "front_wheel_angle": 0.18326515523978895, "heading_rate": 0.43802193912871923, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059816.2294333}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.782, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059816.2294333}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059816.3296072, "x": -88.23608590889674, "y": 40.09283585667525, "z": 202.41153126679097, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1966388162215615, "steering_wheel_angle": 4.19, "front_wheel_angle": 0.20433116498510187, "heading_rate": 0.47677517159027605, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059816.3294592}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.19, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059816.3294592}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059816.429591, "x": -88.23608590889674, "y": 40.09283585667525, "z": 202.41153126679097, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.183278816221561, "steering_wheel_angle": 4.667, "front_wheel_angle": 0.22932907411759154, "heading_rate": 0.5297897641594892, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059816.429464}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.667, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059816.429464}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059816.529682, "x": -88.23608590889674, "y": 40.09283585667525, "z": 202.41153126679097, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": 5.116, "front_wheel_angle": 0.25324025243003173, "heading_rate": 0.5701606130464352, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059816.5294535}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.116, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059816.5294535}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059816.6295621, "x": -88.2361145192969, "y": 40.09282377264589, "z": 202.39866334228518, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": 5.519, "front_wheel_angle": 0.27503112815097713, "heading_rate": 0.5952281243435796, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059816.6294377}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.519, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059816.6294377}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059816.7295547, "x": -88.2361145192969, "y": 40.09282377264589, "z": 202.39866334228518, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": 5.931, "front_wheel_angle": 0.29764589871996416, "heading_rate": 0.6362847698968525, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059816.7294376}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.931, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059816.7294376}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059816.829579, "x": -88.2361145192969, "y": 40.09282377264589, "z": 202.39866334228518, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": 6.241, "front_wheel_angle": 0.31489631141530516, "heading_rate": 0.6552867033954057, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059816.8294384}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.241, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059816.8294384}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059816.9295413, "x": -88.2361145192969, "y": 40.09282377264589, "z": 202.39866334228518, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": 6.444, "front_wheel_angle": 0.32630555964352687, "heading_rate": 0.6701949454731874, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059816.9294338}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059816.9294338}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059817.0295193, "x": -88.2361145192969, "y": 40.09282377264589, "z": 202.39866334228518, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": 6.623, "front_wheel_angle": 0.33644216886484996, "heading_rate": 0.6817175650498276, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059817.0294297}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.623, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059817.0294297}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059817.1296296, "x": -88.23613328143543, "y": 40.09280805199767, "z": 202.36706655244214, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": 6.864, "front_wheel_angle": 0.350205476384925, "heading_rate": 0.6877186685919157, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059817.129432}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.864, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059817.129432}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059817.229555, "x": -88.23613328143543, "y": 40.09280805199767, "z": 202.36706655244214, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": 7.093, "front_wheel_angle": 0.3634097775330191, "heading_rate": 0.7041505912444511, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059817.2294514}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.093, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059817.2294514}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059817.3295648, "x": -88.23613328143543, "y": 40.09280805199767, "z": 202.36706655244214, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": 7.323, "front_wheel_angle": 0.37679925862236247, "heading_rate": 0.7589519149862993, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059817.3294396}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.323, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059817.3294396}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059817.4295423, "x": -88.23613328143543, "y": 40.09280805199767, "z": 202.36706655244214, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": 7.617, "front_wheel_angle": 0.39410660141738396, "heading_rate": 0.7699973308645435, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059817.4294326}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.617, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059817.4294326}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059817.529585, "x": -88.23613328143543, "y": 40.09280805199767, "z": 202.36706655244214, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": 7.983, "front_wheel_angle": 0.4159654993352593, "heading_rate": 0.8041087279879111, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059817.529472}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.983, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059817.529472}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059817.629553, "x": -88.23614257342341, "y": 40.092790716654115, "z": 202.36664953311896, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": 8.325, "front_wheel_angle": 0.4367190682233076, "heading_rate": 0.8350960809878871, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059817.6294572}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.325, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059817.6294572}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059817.7295349, "x": -88.23614257342341, "y": 40.092790716654115, "z": 202.36664953311896, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": 8.689, "front_wheel_angle": 0.4591733238696928, "heading_rate": 0.8517149977302475, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059817.7294304}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.689, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059817.7294304}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059817.8295217, "x": -88.23614257342341, "y": 40.092790716654115, "z": 202.36664953311896, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": 8.989, "front_wheel_angle": 0.47797680875459925, "heading_rate": 0.8924082860267215, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059817.8294272}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.989, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059817.8294272}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059817.9296649, "x": -88.23614257342341, "y": 40.092790716654115, "z": 202.36664953311896, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": 9.237, "front_wheel_angle": 0.493733000507706, "heading_rate": 0.9271211659728351, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059817.9294558}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.237, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059817.9294558}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059818.0296693, "x": -88.23614257342341, "y": 40.092790716654115, "z": 202.36664953311896, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": 9.421, "front_wheel_angle": 0.5055516761184059, "heading_rate": 0.9730073101902869, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059818.0295362}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.421, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059818.0295362}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059818.1297908, "x": -88.23614291214155, "y": 40.09277377084722, "z": 202.32974809553343, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": 9.521, "front_wheel_angle": 0.5120220785161818, "heading_rate": 0.9879195870862042, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059818.1295102}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.521, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059818.1295102}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059818.2296169, "x": -88.23614291214155, "y": 40.09277377084722, "z": 202.32974809553343, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": 9.604, "front_wheel_angle": 0.5174182457061639, "heading_rate": 0.9804304411540785, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059818.229454}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.604, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059818.229454}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059818.3296404, "x": -88.23614291214155, "y": 40.09277377084722, "z": 202.32974809553343, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9592068162215615, "steering_wheel_angle": 9.672, "front_wheel_angle": 0.5218568284899219, "heading_rate": 0.9726093430758719, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059818.329531}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.672, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059818.329531}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059818.4295702, "x": -88.23614291214155, "y": 40.09277377084722, "z": 202.32974809553343, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9592068162215615, "steering_wheel_angle": 9.726, "front_wheel_angle": 0.5253930179043838, "heading_rate": 0.980584444326127, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059818.4294338}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.726, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059818.4294338}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059818.5295637, "x": -88.23614291214155, "y": 40.09277377084722, "z": 202.32974809553343, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9269988162215617, "steering_wheel_angle": 9.798, "front_wheel_angle": 0.5301238437977039, "heading_rate": 0.9363597812925266, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059818.5294333}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.09, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.798, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059818.5294333}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059818.6295478, "x": -88.23613466145447, "y": 40.092759060229916, "z": 202.3135195235245, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9402788162215616, "steering_wheel_angle": 9.818, "front_wheel_angle": 0.531441213647695, "heading_rate": 0.9621526961954223, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059818.629429}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.19, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059818.629429}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059818.7295392, "x": -88.23613466145447, "y": 40.092759060229916, "z": 202.3135195235245, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.975742816221562, "steering_wheel_angle": 9.821, "front_wheel_angle": 0.531638941682323, "heading_rate": 1.022319218680824, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059818.7294278}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.45, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.821, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059818.7294278}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059818.8295865, "x": -88.23613466145447, "y": 40.092759060229916, "z": 202.3135195235245, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9537588162215616, "steering_wheel_angle": 9.821, "front_wheel_angle": 0.531638941682323, "heading_rate": 0.985561673739491, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059818.829429}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.29, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.821, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059818.829429}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059818.9295733, "x": -88.23613466145447, "y": 40.092759060229916, "z": 202.3135195235245, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9074538162215617, "steering_wheel_angle": 9.821, "front_wheel_angle": 0.531638941682323, "heading_rate": 0.9051545441803251, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059818.9294407}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.94, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.821, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059818.9294407}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059819.02957, "x": -88.23613466145447, "y": 40.092759060229916, "z": 202.3135195235245, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8997618162215613, "steering_wheel_angle": 9.827, "front_wheel_angle": 0.5320344938159788, "heading_rate": 0.8921775229750878, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059819.0294385}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.88, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.827, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059819.0294385}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059819.1296518, "x": -88.23612019014696, "y": 40.09274827840149, "z": 202.27340531080134, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9564788162215616, "steering_wheel_angle": 9.832, "front_wheel_angle": 0.5323642185113805, "heading_rate": 0.9918004915090324, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059819.1294372}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.832, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059819.1294372}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059819.2297847, "x": -88.23612019014696, "y": 40.09274827840149, "z": 202.27340531080134, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9443018162215617, "steering_wheel_angle": 9.831, "front_wheel_angle": 0.532298266447191, "heading_rate": 0.9709435992774204, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059819.229488}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.831, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059819.229488}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059819.3295724, "x": -88.23612019014696, "y": 40.09274827840149, "z": 202.27340531080134, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9010388162215617, "steering_wheel_angle": 9.826, "front_wheel_angle": 0.5319685595616759, "heading_rate": 0.8943420488499009, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059819.3294396}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.826, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059819.3294396}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059819.4295423, "x": -88.23612019014696, "y": 40.09274827840149, "z": 202.27340531080134, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9126218162215616, "steering_wheel_angle": 9.819, "front_wheel_angle": 0.5315071194361664, "heading_rate": 0.9140681226960672, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059819.4294307}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.819, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059819.4294307}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059819.5295815, "x": -88.23612019014696, "y": 40.09274827840149, "z": 202.27340531080134, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.919126816221562, "steering_wheel_angle": 9.726, "front_wheel_angle": 0.5253930179043838, "heading_rate": 0.9126455682758182, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059819.529439}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.726, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059819.529439}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059819.6295893, "x": -88.23610233131107, "y": 40.09274251476411, "z": 202.29384840820362, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9113268162215618, "steering_wheel_angle": 9.519, "front_wheel_angle": 0.5118923398800955, "heading_rate": 0.8712998862003534, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059819.6294453}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.519, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059819.6294453}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059819.729589, "x": -88.23610233131107, "y": 40.09274251476411, "z": 202.29384840820362, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9165188162215614, "steering_wheel_angle": 9.158, "front_wheel_angle": 0.4886925781756963, "heading_rate": 0.8328737557597103, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059819.7294436}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.158, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059819.7294436}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059819.8295994, "x": -88.23610233131107, "y": 40.09274251476411, "z": 202.29384840820362, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9256818162215614, "steering_wheel_angle": 8.493, "front_wheel_angle": 0.44703459595765516, "heading_rate": 0.7640484172856419, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059819.8294423}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.493, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059819.8294423}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059819.929597, "x": -88.23610233131107, "y": 40.09274251476411, "z": 202.29384840820362, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9217428162215615, "steering_wheel_angle": 7.628, "front_wheel_angle": 0.39475843520225307, "heading_rate": 0.6591190033646032, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059819.9294403}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.628, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059819.9294403}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059820.0295994, "x": -88.23610233131107, "y": 40.09274251476411, "z": 202.29384840820362, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9443018162215617, "steering_wheel_angle": 6.758, "front_wheel_angle": 0.3441353415842752, "heading_rate": 0.5907942581442971, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059820.0294518}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.758, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059820.0294518}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059820.1295884, "x": -88.23608178496399, "y": 40.09274089866368, "z": 202.31699158686246, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.964686816221562, "steering_wheel_angle": 5.929, "front_wheel_angle": 0.29753526953173426, "heading_rate": 0.5234401768363909, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059820.1294408}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.37, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.929, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059820.1294408}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059820.229577, "x": -88.23608178496399, "y": 40.09274089866368, "z": 202.31699158686246, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9743538162215617, "steering_wheel_angle": 5.089, "front_wheel_angle": 0.2517916237376917, "heading_rate": 0.44617010798608864, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059820.2294455}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.089, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059820.2294455}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059820.3295732, "x": -88.23608178496399, "y": 40.09274089866368, "z": 202.31699158686246, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0096788162215615, "steering_wheel_angle": 4.309, "front_wheel_angle": 0.21052961214945315, "heading_rate": 0.39149807832369987, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059820.3294344}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.309, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059820.3294344}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059820.429559, "x": -88.23608178496399, "y": 40.09274089866368, "z": 202.31699158686246, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": 3.582, "front_wheel_angle": 0.17304126732907615, "heading_rate": 0.3352405086118192, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059820.4294357}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.582, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059820.4294357}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059820.5297077, "x": -88.23608178496399, "y": 40.09274089866368, "z": 202.31699158686246, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": 2.893, "front_wheel_angle": 0.1383155548764554, "heading_rate": 0.27133983548502705, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059820.5294967}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.893, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059820.5294967}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059820.6296039, "x": -88.23605592670508, "y": 40.09274125712121, "z": 202.2954004577931, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": 2.115, "front_wheel_angle": 0.09998093916917623, "heading_rate": 0.20180641013150583, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059820.6294436}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.115, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059820.6294436}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059820.7296622, "x": -88.23605592670508, "y": 40.09274125712121, "z": 202.2954004577931, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": 1.414, "front_wheel_angle": 0.06618633747258527, "heading_rate": 0.13981602607320115, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059820.729466}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.414, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059820.729466}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059820.8295698, "x": -88.23605592670508, "y": 40.09274125712121, "z": 202.2954004577931, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": 0.858, "front_wheel_angle": 0.03985607329215799, "heading_rate": 0.08785443551517448, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059820.8294587}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.858, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059820.8294587}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059820.9295979, "x": -88.23605592670508, "y": 40.09274125712121, "z": 202.2954004577931, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": 0.461, "front_wheel_angle": 0.02130047912639609, "heading_rate": 0.04760045720680088, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059820.9294648}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.461, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059820.9294648}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059821.0296335, "x": -88.23605592670508, "y": 40.09274125712121, "z": 202.2954004577931, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.210126816221561, "steering_wheel_angle": 0.189, "front_wheel_angle": 0.008701273839504779, "heading_rate": 0.02029215463211381, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059821.0294654}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.189, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059821.0294654}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059821.1295273, "x": -88.23602341540129, "y": 40.09274199217284, "z": 202.29948403455273, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.237486816221562, "steering_wheel_angle": -0.117, "front_wheel_angle": -0.005381394392021079, "heading_rate": -0.012886041431209517, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059821.1294277}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.117, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059821.1294277}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059821.2295568, "x": -88.23602341540129, "y": 40.09274199217284, "z": 202.29948403455273, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.267117816221561, "steering_wheel_angle": -0.353, "front_wheel_angle": -0.016286912293893084, "heading_rate": -0.04008461761474898, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059821.229433}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.353, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059821.229433}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059821.3296967, "x": -88.23602341540129, "y": 40.09274199217284, "z": 202.29948403455273, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": -0.363, "front_wheel_angle": -0.016750523259844715, "heading_rate": -0.042272852251847515, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059821.3294606}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.363, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059821.3294606}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059821.429664, "x": -88.23602341540129, "y": 40.09274199217284, "z": 202.29948403455273, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.324461816221562, "steering_wheel_angle": -0.256, "front_wheel_angle": -0.011796291943346152, "heading_rate": -0.03050588870063603, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059821.4294882}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.256, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059821.4294882}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059821.5295668, "x": -88.23602341540129, "y": 40.09274199217284, "z": 202.29948403455273, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.340958816221562, "steering_wheel_angle": -0.122, "front_wheel_angle": -0.005611737772796137, "heading_rate": -0.01470904520703246, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059821.529438}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.122, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059821.529438}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059821.6295555, "x": -88.23598602893475, "y": 40.092742266010234, "z": 202.3259178525316, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": -0.082, "front_wheel_angle": -0.003769840040269683, "heading_rate": -0.010116767096078717, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059821.629433}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.082, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059821.629433}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059821.729537, "x": -88.23598602893475, "y": 40.092742266010234, "z": 202.3259178525316, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.400926816221562, "steering_wheel_angle": -0.095, "front_wheel_angle": -0.004368243991637956, "heading_rate": -0.011995683822778259, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059821.7294307}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.095, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059821.7294307}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059821.8295174, "x": -88.23598602893475, "y": 40.092742266010234, "z": 202.3259178525316, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.400926816221562, "steering_wheel_angle": -0.109, "front_wheel_angle": -0.0050129081195356496, "heading_rate": -0.013766030966575474, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059821.8294277}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.109, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059821.8294277}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059821.929535, "x": -88.23598602893475, "y": 40.092742266010234, "z": 202.3259178525316, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": -0.133, "front_wheel_angle": -0.006118600124947055, "heading_rate": -0.01720877760181965, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059821.9294264}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.133, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059821.9294264}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059822.0296762, "x": -88.23598602893475, "y": 40.092742266010234, "z": 202.3259178525316, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.449201816221562, "steering_wheel_angle": -0.167, "front_wheel_angle": -0.007686196230907832, "heading_rate": -0.02185805097382793, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059822.0294461}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.167, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059822.0294461}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059822.1299646, "x": -88.23598602893475, "y": 40.092742266010234, "z": 202.3259178525316, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.464913816221562, "steering_wheel_angle": -0.161, "front_wheel_angle": -0.0074094593292757605, "heading_rate": -0.021302585411029345, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059822.1295419}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059822.1295419}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059822.2296002, "x": -88.23594492409232, "y": 40.09274259262578, "z": 202.31739513649933, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.480753816221561, "steering_wheel_angle": -0.117, "front_wheel_angle": -0.005381394392021079, "heading_rate": -0.015639828425481044, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059822.2294686}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.117, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059822.2294686}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059822.3303223, "x": -88.23594492409232, "y": 40.09274259262578, "z": 202.31739513649933, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.514838816221562, "steering_wheel_angle": -0.064, "front_wheel_angle": -0.0029416185228755055, "heading_rate": -0.008744445909401427, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059822.3295765}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.064, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059822.3295765}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059822.4296842, "x": -88.23594492409232, "y": 40.09274259262578, "z": 202.31739513649933, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.531078816221561, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059822.4294987}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.69, "gear": 0, "accelerator_pedal_position": 0.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": 1744059822.4294987}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059822.5295835, "x": -88.23594492409232, "y": 40.09274259262578, "z": 202.31739513649933, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.547446816221561, "steering_wheel_angle": 0.038, "front_wheel_angle": 0.0017459900665104152, "heading_rate": 0.005299358047806088, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059822.529462}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.038, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059822.529462}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059822.6296127, "x": -88.23590077516819, "y": 40.09274307110068, "z": 202.3134082554711, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.563942816221561, "steering_wheel_angle": 0.063, "front_wheel_angle": 0.002895617708822582, "heading_rate": 0.008879165056046228, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059822.6294522}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.063, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059822.6294522}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059822.7295568, "x": -88.23590077516819, "y": 40.09274307110068, "z": 202.3134082554711, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.580566816221562, "steering_wheel_angle": 0.06, "front_wheel_angle": 0.0027576225208671363, "heading_rate": 0.008542188289888088, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059822.7294314}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.06, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059822.7294314}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059822.82955, "x": -88.23590077516819, "y": 40.09274307110068, "z": 202.3134082554711, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": 0.055, "front_wheel_angle": 0.002527654715902418, "heading_rate": 0.007918685153931303, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059822.8294308}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.055, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059822.8294308}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059822.92957, "x": -88.23590077516819, "y": 40.09274307110068, "z": 202.3134082554711, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.633341816221561, "steering_wheel_angle": 0.055, "front_wheel_angle": 0.002527654715902418, "heading_rate": 0.008076663910119459, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059822.9294384}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.055, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059822.9294384}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059823.029835, "x": -88.23590077516819, "y": 40.09274307110068, "z": 202.3134082554711, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.633341816221561, "steering_wheel_angle": 0.065, "front_wheel_angle": 0.002987620546121671, "heading_rate": 0.00954640967965433, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059823.0294664}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.065, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059823.0294664}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059823.1297154, "x": -88.23585414617449, "y": 40.092743505370834, "z": 202.32541895547112, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.650493816221561, "steering_wheel_angle": 0.091, "front_wheel_angle": 0.004184097889882324, "heading_rate": 0.013500332129891731, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059823.12945}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.26, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.091, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059823.12945}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059823.229719, "x": -88.23585414617449, "y": 40.092743505370834, "z": 202.32541895547112, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.667773816221562, "steering_wheel_angle": 0.097, "front_wheel_angle": 0.0044603243150626555, "heading_rate": 0.014530996670063353, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059823.2294836}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.097, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059823.2294836}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059823.3295965, "x": -88.23585414617449, "y": 40.092743505370834, "z": 202.32541895547112, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.687366816221561, "steering_wheel_angle": 0.11, "front_wheel_angle": 0.00505896465535069, "heading_rate": 0.0166591546376002, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059823.3294647}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059823.3294647}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059823.4295542, "x": -88.23585414617449, "y": 40.092743505370834, "z": 202.32541895547112, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.704918816221562, "steering_wheel_angle": 0.139, "front_wheel_angle": 0.006395132496591273, "heading_rate": 0.0212591091710555, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059823.4294558}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.51, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.139, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059823.4294558}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059823.5295298, "x": -88.23585414617449, "y": 40.092743505370834, "z": 202.32541895547112, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.722598816221561, "steering_wheel_angle": 0.134, "front_wheel_angle": 0.006164685813487009, "heading_rate": 0.02068567264301516, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059823.5294273}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.59, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.134, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059823.5294273}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059823.6296575, "x": -88.23580535562542, "y": 40.092744347164924, "z": 202.3295556240863, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.740406816221562, "steering_wheel_angle": 0.135, "front_wheel_angle": 0.00621077271792595, "heading_rate": 0.02103441087481962, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059823.6295054}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.135, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059823.6295054}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059823.7295983, "x": -88.23580535562542, "y": 40.092744347164924, "z": 202.3295556240863, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.740406816221562, "steering_wheel_angle": 0.137, "front_wheel_angle": 0.00630295017488376, "heading_rate": 0.021346602218452644, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059823.729465}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.137, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059823.729465}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059823.8296018, "x": -88.23580535562542, "y": 40.092744347164924, "z": 202.3295556240863, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.758342816221561, "steering_wheel_angle": 0.135, "front_wheel_angle": 0.00621077271792595, "heading_rate": 0.02122850001783987, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059823.8294628}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.75, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.135, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059823.8294628}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059823.929598, "x": -88.23580535562542, "y": 40.092744347164924, "z": 202.3295556240863, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.758342816221561, "steering_wheel_angle": 0.125, "front_wheel_angle": 0.005749958377428514, "heading_rate": 0.019653394641979804, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059823.9294624}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.75, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.125, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059823.9294624}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059824.0297396, "x": -88.23580535562542, "y": 40.092744347164924, "z": 202.3295556240863, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.796881816221561, "steering_wheel_angle": 0.115, "front_wheel_angle": 0.005289265540233417, "heading_rate": 0.018429956484585917, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059824.029466}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.115, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059824.029466}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059824.1295934, "x": -88.23575478840573, "y": 40.09274592818494, "z": 202.32121976705335, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.796881816221561, "steering_wheel_angle": 0.111, "front_wheel_angle": 0.005105022404758634, "heading_rate": 0.01778796696742297, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059824.1294646}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.111, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059824.1294646}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059824.2295227, "x": -88.23575478840573, "y": 40.09274592818494, "z": 202.32121976705335, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.796881816221561, "steering_wheel_angle": 0.138, "front_wheel_angle": 0.006349040727595683, "heading_rate": 0.02212273604419122, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059824.2294245}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.138, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059824.2294245}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059824.3296187, "x": -88.23575478840573, "y": 40.09274592818494, "z": 202.32121976705335, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.815217816221562, "steering_wheel_angle": 0.146, "front_wheel_angle": 0.006717808943590281, "heading_rate": 0.02361765234838426, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059824.3294652}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.146, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059824.3294652}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059824.4295485, "x": -88.23575478840573, "y": 40.09274592818494, "z": 202.32121976705335, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.815217816221562, "steering_wheel_angle": 0.142, "front_wheel_angle": 0.006533415102241901, "heading_rate": 0.022969364289447763, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059824.4294293}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.142, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059824.4294293}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059824.5296786, "x": -88.23575478840573, "y": 40.09274592818494, "z": 202.32121976705335, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.852273816221562, "steering_wheel_angle": 0.14, "front_wheel_angle": 0.0064412254819663445, "heading_rate": 0.023047828675293695, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059824.529466}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059824.529466}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059824.6295977, "x": -88.23570250129345, "y": 40.09274817261899, "z": 202.31324754522325, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.852273816221562, "steering_wheel_angle": 0.141, "front_wheel_angle": 0.006487319683817855, "heading_rate": 0.023212766383449164, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059824.6294663}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.141, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059824.6294663}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059824.729683, "x": -88.23570250129345, "y": 40.09274817261899, "z": 202.31324754522325, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.870993816221562, "steering_wheel_angle": 0.141, "front_wheel_angle": 0.006487319683817855, "heading_rate": 0.023415497967584093, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059824.729463}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.141, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059824.729463}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059824.82993, "x": -88.23570250129345, "y": 40.09274817261899, "z": 202.31324754522325, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": 0.139, "front_wheel_angle": 0.006395132496591273, "heading_rate": 0.023307577974846984, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059824.8295135}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.139, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059824.8295135}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059824.929601, "x": -88.23570250129345, "y": 40.09274817261899, "z": 202.31324754522325, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": 0.137, "front_wheel_angle": 0.00630295017488376, "heading_rate": 0.022971603079372918, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059824.929465}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.137, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059824.929465}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059825.0295453, "x": -88.23570250129345, "y": 40.09274817261899, "z": 202.31324754522325, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.911198816221562, "steering_wheel_angle": 0.129, "front_wheel_angle": 0.005934269527847416, "heading_rate": 0.021813332719713828, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059825.0294285}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.129, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059825.0294285}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059825.1295564, "x": -88.23564871642606, "y": 40.09275095832017, "z": 202.33575537781948, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.911198816221562, "steering_wheel_angle": 0.104, "front_wheel_angle": 0.004782643640989698, "heading_rate": 0.01758008586160667, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059825.1294608}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.104, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059825.1294608}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059825.229623, "x": -88.23564871642606, "y": 40.09275095832017, "z": 202.33575537781948, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.930318816221561, "steering_wheel_angle": 0.056, "front_wheel_angle": 0.0025736458598437915, "heading_rate": 0.009540606693439445, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059825.229462}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.49, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.056, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059825.229462}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059825.3295975, "x": -88.23564871642606, "y": 40.09275095832017, "z": 202.33575537781948, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.930318816221561, "steering_wheel_angle": 0.008, "front_wheel_angle": 0.00036743230800517036, "heading_rate": 0.0013620831093314838, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059825.3294668}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.49, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.008, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059825.3294668}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059825.429593, "x": -88.23564871642606, "y": 40.09275095832017, "z": 202.33575537781948, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.930318816221561, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059825.4294586}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.49, "gear": 0, "accelerator_pedal_position": 0.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": 1744059825.4294586}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059825.5296955, "x": -88.23564871642606, "y": 40.09275095832017, "z": 202.33575537781948, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.949566816221562, "steering_wheel_angle": 0.007, "front_wheel_angle": 0.00032149905694411315, "heading_rate": 0.0012018539378753936, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059825.5294573}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.007, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059825.5294573}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059825.6295924, "x": -88.23559383305633, "y": 40.09275422613484, "z": 202.3368392415583, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.949566816221562, "steering_wheel_angle": 0.005, "front_wheel_angle": 0.0002296361660609387, "heading_rate": 0.0008584445889968803, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059825.629435}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.005, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059825.629435}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059825.7295635, "x": -88.23559383305633, "y": 40.09275422613484, "z": 202.3368392415583, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.968942816221562, "steering_wheel_angle": -0.009, "front_wheel_angle": -0.00041336676293914716, "heading_rate": -0.001558199019361361, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059825.729434}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.009, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059825.729434}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059825.8295078, "x": -88.23559383305633, "y": 40.09275422613484, "z": 202.3368392415583, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.968942816221562, "steering_wheel_angle": -0.006, "front_wheel_angle": -0.00027556700966073483, "heading_rate": -0.0010387584806786543, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059825.8294213}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.006, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059825.8294213}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059825.9295552, "x": -88.23559383305633, "y": 40.09275422613484, "z": 202.3368392415583, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.990893816221561, "steering_wheel_angle": -0.002, "front_wheel_angle": -9.1850856414927e-05, "heading_rate": -0.0003494638062489273, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059825.9294271}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.002, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059825.9294271}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059826.0296998, "x": -88.23559383305633, "y": 40.09275422613484, "z": 202.3368392415583, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.010541816221561, "steering_wheel_angle": 0.014, "front_wheel_angle": 0.0006430570990113664, "heading_rate": 0.0024667271807545976, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059826.0294428}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.014, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059826.0294428}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059826.1295867, "x": -88.2355380221234, "y": 40.092757570152514, "z": 202.34768397971658, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.010541816221561, "steering_wheel_angle": 0.054, "front_wheel_angle": 0.0024816647802959747, "heading_rate": 0.009519530535692185, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059826.1294377}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.054, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059826.1294377}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059826.229593, "x": -88.2355380221234, "y": 40.092757570152514, "z": 202.34768397971658, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.010541816221561, "steering_wheel_angle": 0.107, "front_wheel_angle": 0.0049207986882990285, "heading_rate": 0.018876028574995866, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059826.2294614}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.107, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059826.2294614}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059826.329701, "x": -88.2355380221234, "y": 40.092757570152514, "z": 202.34768397971658, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.030317816221562, "steering_wheel_angle": 0.086, "front_wheel_angle": 0.003953942526841233, "heading_rate": 0.015290716798898752, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059826.3294446}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.9, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.086, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059826.3294446}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059826.4295819, "x": -88.2355380221234, "y": 40.092757570152514, "z": 202.34768397971658, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.050221816221562, "steering_wheel_angle": -0.061, "front_wheel_angle": -0.002803619707913495, "heading_rate": -0.01092976484210065, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059826.4294577}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.061, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059826.4294577}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059826.5295956, "x": -88.2355380221234, "y": 40.092757570152514, "z": 202.34768397971658, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.030317816221562, "steering_wheel_angle": -0.299, "front_wheel_angle": -0.013785548596772742, "heading_rate": -0.05331467858803829, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059826.5294633}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.9, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.299, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059826.5294633}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059826.6295185, "x": -88.23548145775584, "y": 40.09276119430228, "z": 202.3683779252951, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.050221816221562, "steering_wheel_angle": -0.596, "front_wheel_angle": -0.027587924106941566, "heading_rate": -0.10757709134756195, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059826.6294212}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.596, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059826.6294212}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059826.7295494, "x": -88.23548145775584, "y": 40.09276119430228, "z": 202.3683779252951, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.030317816221562, "steering_wheel_angle": -0.805, "front_wheel_angle": -0.037367270139572056, "heading_rate": -0.1445735362210315, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059826.7294245}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.9, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.805, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059826.7294245}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059826.8295827, "x": -88.23548145775584, "y": 40.09276119430228, "z": 202.3683779252951, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.050221816221562, "steering_wheel_angle": -0.856, "front_wheel_angle": -0.03976209054917526, "heading_rate": -0.15509176808604822, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059826.8294597}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.856, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059826.8294597}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059826.9297218, "x": -88.23548145775584, "y": 40.09276119430228, "z": 202.3683779252951, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.030317816221562, "steering_wheel_angle": -0.854, "front_wheel_angle": -0.03966811296157078, "heading_rate": -0.1534845447119463, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059826.9294944}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.9, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.854, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059826.9294944}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059827.02962, "x": -88.23548145775584, "y": 40.09276119430228, "z": 202.3683779252951, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.050221816221562, "steering_wheel_angle": -0.875, "front_wheel_angle": -0.040655134875872675, "heading_rate": -0.1585788805014341, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059827.0294404}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.875, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059827.0294404}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059827.1296341, "x": -88.23542362062193, "y": 40.09276302618682, "z": 202.35849873305355, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.010541816221561, "steering_wheel_angle": -0.939, "front_wheel_angle": -0.04366671696330783, "heading_rate": -0.16760934214778692, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059827.1294806}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.939, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059827.1294806}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059827.2295656, "x": -88.23542362062193, "y": 40.09276302618682, "z": 202.35849873305355, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.010541816221561, "steering_wheel_angle": -0.994, "front_wheel_angle": -0.046259040995053576, "heading_rate": -0.17757347123076042, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059827.2294314}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.994, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059827.2294314}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059827.3295557, "x": -88.23542362062193, "y": 40.09276302618682, "z": 202.35849873305355, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.968942816221562, "steering_wheel_angle": -0.935, "front_wheel_angle": -0.04347833765030932, "heading_rate": -0.16399630316636601, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059827.3294282}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.935, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059827.3294282}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059827.4295537, "x": -88.23542362062193, "y": 40.09276302618682, "z": 202.35849873305355, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.968942816221562, "steering_wheel_angle": -0.742, "front_wheel_angle": -0.03441356996258945, "heading_rate": -0.12977426172769518, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059827.4294515}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.742, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059827.4294515}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059827.5295434, "x": -88.23542362062193, "y": 40.09276302618682, "z": 202.35849873305355, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.990893816221561, "steering_wheel_angle": -0.474, "front_wheel_angle": -0.021904943128487286, "heading_rate": -0.08335479568320749, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059827.5294263}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.474, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059827.5294263}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059827.629588, "x": -88.23536613923841, "y": 40.09276070544368, "z": 202.32865850662708, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": -0.229, "front_wheel_angle": -0.010548384515803491, "heading_rate": -0.03844534293290823, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059827.6294575}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059827.6294575}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059827.729556, "x": -88.23536613923841, "y": 40.09276070544368, "z": 202.32865850662708, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.911198816221562, "steering_wheel_angle": -0.022, "front_wheel_angle": -0.0010106242725761874, "heading_rate": -0.0037148350166602484, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059827.7294295}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.022, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059827.7294295}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059827.829594, "x": -88.23536613923841, "y": 40.09276070544368, "z": 202.32865850662708, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.796881816221561, "steering_wheel_angle": 0.178, "front_wheel_angle": 0.008193661216406963, "heading_rate": 0.02855042722507238, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059827.8294613}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.178, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059827.8294613}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059827.9299057, "x": -88.23536613923841, "y": 40.09276070544368, "z": 202.32865850662708, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.815217816221562, "steering_wheel_angle": 0.423, "front_wheel_angle": 0.01953479291157144, "heading_rate": 0.06868574356483939, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059827.9295022}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.423, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059827.9295022}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059828.029789, "x": -88.23536613923841, "y": 40.09276070544368, "z": 202.32865850662708, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.722598816221561, "steering_wheel_angle": 0.745, "front_wheel_angle": 0.03455410722842395, "heading_rate": 0.11599139471057927, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059828.0294793}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.59, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.745, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059828.0294793}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059828.129709, "x": -88.23531357237118, "y": 40.09275732221545, "z": 202.35428157503262, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.667773816221562, "steering_wheel_angle": 1.099, "front_wheel_angle": 0.05121898885867858, "heading_rate": 0.16700792971170067, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059828.1294444}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.099, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059828.1294444}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059828.2296133, "x": -88.23531357237118, "y": 40.09275732221545, "z": 202.35428157503262, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": 1.534, "front_wheel_angle": 0.0719232373850156, "heading_rate": 0.22796283418648677, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059828.2294252}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.534, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059828.2294252}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059828.329587, "x": -88.23531357237118, "y": 40.09275732221545, "z": 202.35428157503262, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.580566816221562, "steering_wheel_angle": 2.045, "front_wheel_angle": 0.09657531185242996, "heading_rate": 0.3000906599145434, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059828.3294508}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.045, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059828.3294508}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059828.4296556, "x": -88.23531357237118, "y": 40.09275732221545, "z": 202.35428157503262, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.514838816221562, "steering_wheel_angle": 2.536, "front_wheel_angle": 0.12061321802918615, "heading_rate": 0.360290447409511, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059828.429482}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.536, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059828.429482}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059828.52961, "x": -88.23531357237118, "y": 40.09275732221545, "z": 202.35428157503262, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.480753816221561, "steering_wheel_angle": 2.924, "front_wheel_angle": 0.13986189946624047, "heading_rate": 0.4091449401321106, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059828.5294585}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.924, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059828.5294585}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059828.629772, "x": -88.23526852830757, "y": 40.0927574394862, "z": 202.38747896137818, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": 3.243, "front_wheel_angle": 0.1558612541515431, "heading_rate": 0.44194426410765375, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059828.6294627}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.243, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059828.6294627}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059828.7295866, "x": -88.23526852830757, "y": 40.0927574394862, "z": 202.38747896137818, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": 3.518, "front_wheel_angle": 0.16978356728649616, "heading_rate": 0.4654165785770933, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059828.7294333}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.518, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059828.7294333}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059828.829858, "x": -88.23526852830757, "y": 40.0927574394862, "z": 202.38747896137818, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.355758816221561, "steering_wheel_angle": 3.695, "front_wheel_angle": 0.17880960400083964, "heading_rate": 0.4793845598417833, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059828.8294787}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.695, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059828.8294787}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059828.9296737, "x": -88.23526852830757, "y": 40.0927574394862, "z": 202.38747896137818, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3099338162215615, "steering_wheel_angle": 3.828, "front_wheel_angle": 0.18562608284343493, "heading_rate": 0.47973946714796045, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059828.9294722}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.54, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.828, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059828.9294722}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059829.0295606, "x": -88.23526852830757, "y": 40.0927574394862, "z": 202.38747896137818, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": 3.994, "front_wheel_angle": 0.19417568707260924, "heading_rate": 0.490097334277456, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059829.0294425}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.994, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059829.0294425}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059829.12956, "x": -88.23523157614969, "y": 40.092763423130044, "z": 202.39111960533893, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.237486816221562, "steering_wheel_angle": 4.243, "front_wheel_angle": 0.2070887483082823, "heading_rate": 0.5030929651762454, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059829.1294272}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.243, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059829.1294272}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059829.2299573, "x": -88.23523157614969, "y": 40.092763423130044, "z": 202.39111960533893, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.210126816221561, "steering_wheel_angle": 4.582, "front_wheel_angle": 0.22484457752588818, "heading_rate": 0.5333630926175231, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059829.229516}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.582, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059829.229516}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059829.3300583, "x": -88.23523157614969, "y": 40.092763423130044, "z": 202.39111960533893, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1966388162215615, "steering_wheel_angle": 4.904, "front_wheel_angle": 0.24190319164845872, "heading_rate": 0.5676828286148419, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059829.3296788}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.904, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059829.3296788}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059829.429616, "x": -88.23523157614969, "y": 40.092763423130044, "z": 202.39111960533893, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": 5.247, "front_wheel_angle": 0.2602887420472386, "heading_rate": 0.5867599139279168, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059829.4294415}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.247, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059829.4294415}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059829.5295668, "x": -88.23523157614969, "y": 40.092763423130044, "z": 202.39111960533893, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.142353816221561, "steering_wheel_angle": 5.609, "front_wheel_angle": 0.2799416098960318, "heading_rate": 0.6243947514216049, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059829.5294385}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.609, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059829.5294385}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059829.6295605, "x": -88.23520301915975, "y": 40.09277466430896, "z": 202.3908181964615, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": 5.914, "front_wheel_angle": 0.2967058185043381, "heading_rate": 0.6341519618855396, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059829.62943}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.914, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059829.62943}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059829.7295568, "x": -88.23520301915975, "y": 40.09277466430896, "z": 202.3908181964615, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": 6.097, "front_wheel_angle": 0.30685762380207404, "heading_rate": 0.6473476696060455, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059829.729427}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.097, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059829.729427}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059829.8295097, "x": -88.23520301915975, "y": 40.09277466430896, "z": 202.3908181964615, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": 6.317, "front_wheel_angle": 0.31915712206986296, "heading_rate": 0.6544542645891956, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059829.8294194}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059829.8294194}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059829.9296207, "x": -88.23520301915975, "y": 40.09277466430896, "z": 202.3908181964615, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": 6.617, "front_wheel_angle": 0.33610121958628014, "heading_rate": 0.7137239287223656, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059829.929432}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.617, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059829.929432}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059830.0295408, "x": -88.23520301915975, "y": 40.09277466430896, "z": 202.3908181964615, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": 6.833, "front_wheel_angle": 0.34842753408664434, "heading_rate": 0.7194003722422889, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059830.0294218}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.833, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059830.0294218}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059830.1295698, "x": -88.23518294784633, "y": 40.092789113663684, "z": 202.39255144439093, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": 7.094, "front_wheel_angle": 0.36346771340361284, "heading_rate": 0.7295321303545921, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059830.1294332}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.094, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059830.1294332}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059830.2295797, "x": -88.23518294784633, "y": 40.092789113663684, "z": 202.39255144439093, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": 7.416, "front_wheel_angle": 0.3822504000901468, "heading_rate": 0.7569367181391149, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059830.2294314}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059830.2294314}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059830.32957, "x": -88.23518294784633, "y": 40.092789113663684, "z": 202.39255144439093, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": 7.764, "front_wheel_angle": 0.4028434687119659, "heading_rate": 0.7890415310204907, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059830.3294291}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059830.3294291}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059830.4296517, "x": -88.23518294784633, "y": 40.092789113663684, "z": 202.39255144439093, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": 8.018, "front_wheel_angle": 0.4180745820914484, "heading_rate": 0.808701367885618, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059830.4294703}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.018, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059830.4294703}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059830.529573, "x": -88.23518294784633, "y": 40.092789113663684, "z": 202.39255144439093, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": 8.347, "front_wheel_angle": 0.4380653063066225, "heading_rate": 0.8526693011412926, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059830.5294251}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.347, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059830.5294251}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059830.6295202, "x": -88.23517219067729, "y": 40.09280557531507, "z": 202.3891440259857, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": 8.641, "front_wheel_angle": 0.45619006810781915, "heading_rate": 0.8779153902534174, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059830.629417}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.641, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059830.629417}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059830.7295284, "x": -88.23517219067729, "y": 40.09280557531507, "z": 202.3891440259857, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": 8.641, "front_wheel_angle": 0.45619006810781915, "heading_rate": 0.8625806236114362, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059830.7294202}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.641, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059830.7294202}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059830.8300176, "x": -88.23517219067729, "y": 40.09280557531507, "z": 202.3891440259857, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": 8.781, "front_wheel_angle": 0.4649105434377169, "heading_rate": 0.8816830073323945, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059830.829534}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.781, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059830.829534}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059830.9295576, "x": -88.23517219067729, "y": 40.09280557531507, "z": 202.3891440259857, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": 8.926, "front_wheel_angle": 0.4740051452453035, "heading_rate": 0.9017838039932389, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059830.9294274}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.926, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059830.9294274}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059831.0295565, "x": -88.23517219067729, "y": 40.09280557531507, "z": 202.3891440259857, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9592068162215615, "steering_wheel_angle": 9.11, "front_wheel_angle": 0.48563983349466683, "heading_rate": 0.8927249963035347, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059831.0294285}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.11, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059831.0294285}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059831.1296737, "x": -88.2351709300441, "y": 40.09282226596771, "z": 202.42857190104465, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9483428162215617, "steering_wheel_angle": 9.256, "front_wheel_angle": 0.49494826655742297, "heading_rate": 0.8960877335476348, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059831.1294768}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.25, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.256, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059831.1294768}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059831.2295575, "x": -88.2351709300441, "y": 40.09282226596771, "z": 202.42857190104465, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9483428162215617, "steering_wheel_angle": 9.268, "front_wheel_angle": 0.4957164082434564, "heading_rate": 0.8977351817582767, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059831.2294304}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.25, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.268, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059831.2294304}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059831.3295774, "x": -88.2351709300441, "y": 40.09282226596771, "z": 202.42857190104465, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": 9.266, "front_wheel_angle": 0.49558835204165075, "heading_rate": 0.9671456059067025, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059831.3294547}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.266, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059831.3294547}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059831.4295459, "x": -88.2351709300441, "y": 40.09282226596771, "z": 202.42857190104465, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9126218162215616, "steering_wheel_angle": 9.242, "front_wheel_angle": 0.49405269362533016, "heading_rate": 0.8373626931361552, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059831.4294517}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059831.4294517}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059831.529561, "x": -88.2351709300441, "y": 40.09282226596771, "z": 202.42857190104465, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.968817816221562, "steering_wheel_angle": 9.175, "front_wheel_angle": 0.48977552770561933, "heading_rate": 0.9162653600278776, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059831.5294154}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.175, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059831.5294154}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059831.6295435, "x": -88.2351775784208, "y": 40.09283711497607, "z": 202.48320489610913, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9309618162215614, "steering_wheel_angle": 9.117, "front_wheel_angle": 0.4860845672741636, "heading_rate": 0.8503442102157909, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059831.6294215}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.117, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059831.6294215}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059831.7295914, "x": -88.2351775784208, "y": 40.09283711497607, "z": 202.48320489610913, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9537588162215616, "steering_wheel_angle": 9.028, "front_wheel_angle": 0.4804416695389454, "heading_rate": 0.8733708539407035, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059831.7294567}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.29, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.028, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059831.7294567}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059831.8297534, "x": -88.2351775784208, "y": 40.09283711497607, "z": 202.48320489610913, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9605738162215616, "steering_wheel_angle": 8.807, "front_wheel_angle": 0.4665365688438582, "heading_rate": 0.8537872353091759, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059831.829526}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.807, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059831.829526}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059831.9295838, "x": -88.2351775784208, "y": 40.09283711497607, "z": 202.48320489610913, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9619428162215615, "steering_wheel_angle": 8.5, "front_wheel_angle": 0.44746617845758285, "heading_rate": 0.8155125291356462, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059831.9294536}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.35, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.5, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059831.9294536}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059832.0295835, "x": -88.2351775784208, "y": 40.09283711497607, "z": 202.48320489610913, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9785268162215615, "steering_wheel_angle": 8.189, "front_wheel_angle": 0.42842724239976887, "heading_rate": 0.797473900086992, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059832.029452}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.47, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.189, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059832.029452}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059832.1296706, "x": -88.2351775784208, "y": 40.09283711497607, "z": 202.48320489610913, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": 7.937, "front_wheel_angle": 0.41319861128693286, "heading_rate": 0.7843954074827963, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059832.1294467}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.937, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059832.1294467}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059832.2295716, "x": -88.23519058623842, "y": 40.092849806336766, "z": 202.51631376559664, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.025617816221562, "steering_wheel_angle": 7.631, "front_wheel_angle": 0.39493626235204365, "heading_rate": 0.781569408748992, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059832.2294528}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.8, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.631, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059832.2294528}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059832.3296947, "x": -88.23519058623842, "y": 40.092849806336766, "z": 202.51631376559664, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.038838816221562, "steering_wheel_angle": 7.332, "front_wheel_angle": 0.37732584439704514, "heading_rate": 0.7570240658992324, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059832.3294213}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.332, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059832.3294213}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059832.429558, "x": -88.23519058623842, "y": 40.092849806336766, "z": 202.51631376559664, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": 7.033, "front_wheel_angle": 0.3599380347245163, "heading_rate": 0.7453139811625293, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059832.4294262}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.033, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059832.4294262}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059832.5296617, "x": -88.23519058623842, "y": 40.092849806336766, "z": 202.51631376559664, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": 6.845, "front_wheel_angle": 0.34911550270355035, "heading_rate": 0.7436946926644187, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059832.529468}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.845, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059832.529468}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059832.6295907, "x": -88.23521045380178, "y": 40.09286084423762, "z": 202.5833128644393, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": 6.705, "front_wheel_angle": 0.3411100608015936, "heading_rate": 0.7363193050789658, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059832.629459}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.705, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059832.629459}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059832.7298179, "x": -88.23521045380178, "y": 40.09286084423762, "z": 202.5833128644393, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": 6.51, "front_wheel_angle": 0.3300346763692049, "heading_rate": 0.7333002334466378, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059832.7294815}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.51, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059832.7294815}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059832.8295794, "x": -88.23521045380178, "y": 40.09286084423762, "z": 202.5833128644393, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": 6.115, "front_wheel_angle": 0.30786001432115107, "heading_rate": 0.7005266623295956, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059832.8294516}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.115, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059832.8294516}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059832.9295545, "x": -88.23521045380178, "y": 40.09286084423762, "z": 202.5833128644393, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.183278816221561, "steering_wheel_angle": 5.498, "front_wheel_angle": 0.27388769482147307, "heading_rate": 0.6376205794661162, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059832.9294255}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.498, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059832.9294255}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059833.029565, "x": -88.23521045380178, "y": 40.09286084423762, "z": 202.5833128644393, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.210126816221561, "steering_wheel_angle": 4.861, "front_wheel_angle": 0.23961405355429782, "heading_rate": 0.5697331490122265, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059833.0294244}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.861, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059833.0294244}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059833.1295424, "x": -88.23523853452686, "y": 40.09286914083179, "z": 202.54410804744504, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.237486816221562, "steering_wheel_angle": 4.497, "front_wheel_angle": 0.22037320280022, "heading_rate": 0.5364021043938156, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059833.1294403}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.497, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059833.1294403}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059833.2296, "x": -88.23523853452686, "y": 40.09286914083179, "z": 202.54410804744504, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.267117816221561, "steering_wheel_angle": 4.313, "front_wheel_angle": 0.210738396082821, "heading_rate": 0.5264302326350366, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059833.2294257}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.313, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059833.2294257}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059833.3295581, "x": -88.23523853452686, "y": 40.09286914083179, "z": 202.54410804744504, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": 4.17, "front_wheel_angle": 0.20329184272348538, "heading_rate": 0.5137381488791166, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059833.3294275}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.17, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059833.3294275}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059833.4297633, "x": -88.23523853452686, "y": 40.09286914083179, "z": 202.54410804744504, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": 3.866, "front_wheel_angle": 0.18757910004151246, "heading_rate": 0.47897508335848143, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059833.4294958}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.866, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059833.4294958}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059833.5295966, "x": -88.23523853452686, "y": 40.09286914083179, "z": 202.54410804744504, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.324461816221562, "steering_wheel_angle": 3.423, "front_wheel_angle": 0.1649602412103384, "heading_rate": 0.43048877913512384, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059833.5294576}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.423, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059833.5294576}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059833.6297073, "x": -88.23527302872235, "y": 40.092872907848424, "z": 202.5396730000746, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.324461816221562, "steering_wheel_angle": 2.907, "front_wheel_angle": 0.13901372058557984, "heading_rate": 0.36181446708061193, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059833.6294727}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.907, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059833.6294727}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059833.7295985, "x": -88.23527302872235, "y": 40.092872907848424, "z": 202.5396730000746, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": 2.269, "front_wheel_angle": 0.10749813009545346, "heading_rate": 0.28959768600067687, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059833.7294905}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.269, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059833.7294905}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059833.8299403, "x": -88.23527302872235, "y": 40.092872907848424, "z": 202.5396730000746, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": 1.603, "front_wheel_angle": 0.07523083754525545, "heading_rate": 0.20462615429667685, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059833.8294656}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.603, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059833.8294656}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059833.9296348, "x": -88.23527302872235, "y": 40.092872907848424, "z": 202.5396730000746, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.400926816221562, "steering_wheel_angle": 0.988, "front_wheel_angle": 0.04597605070017692, "heading_rate": 0.1263435795947297, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059833.9294324}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.988, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059833.9294324}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059834.0295775, "x": -88.23527302872235, "y": 40.092872907848424, "z": 202.5396730000746, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": 0.567, "front_wheel_angle": 0.026235357021001153, "heading_rate": 0.07298383225999096, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059834.0294666}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.567, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059834.0294666}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059834.12958, "x": -88.23531222694214, "y": 40.092873267829496, "z": 202.51666090806734, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.449201816221562, "steering_wheel_angle": 0.392, "front_wheel_angle": 0.018095695661081455, "heading_rate": 0.05146525216318589, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059834.1294541}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.392, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059834.1294541}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059834.2296782, "x": -88.23531222694214, "y": 40.092873267829496, "z": 202.51666090806734, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.464913816221562, "steering_wheel_angle": 0.282, "front_wheel_angle": 0.012998826464549688, "heading_rate": 0.0373737311160481, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059834.2294538}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.282, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059834.2294538}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059834.329585, "x": -88.23531222694214, "y": 40.092873267829496, "z": 202.51666090806734, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.480753816221561, "steering_wheel_angle": 0.199, "front_wheel_angle": 0.00916286808426341, "heading_rate": 0.026630330651840763, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059834.3294494}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.199, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059834.3294494}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059834.4295876, "x": -88.23531222694214, "y": 40.092873267829496, "z": 202.51666090806734, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.514838816221562, "steering_wheel_angle": 0.15, "front_wheel_angle": 0.006902222257807445, "heading_rate": 0.02051825996916034, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059834.4294229}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.15, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059834.4294229}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059834.529514, "x": -88.23531222694214, "y": 40.092873267829496, "z": 202.51666090806734, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.531078816221561, "steering_wheel_angle": 0.107, "front_wheel_angle": 0.0049207986882990285, "heading_rate": 0.014781737244574157, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059834.5294137}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.107, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059834.5294137}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059834.629666, "x": -88.23535512070329, "y": 40.09287269670172, "z": 202.52206396905402, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.531078816221561, "steering_wheel_angle": 0.044, "front_wheel_angle": 0.002021831861724432, "heading_rate": 0.006073401641510742, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059834.6294577}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.044, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059834.6294577}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059834.729504, "x": -88.23535512070329, "y": 40.09287269670172, "z": 202.52206396905402, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.580566816221562, "steering_wheel_angle": -0.027, "front_wheel_angle": -0.0012403929219419797, "heading_rate": -0.0038423128576711946, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059834.7294128}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059834.7294128}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059834.829529, "x": -88.23535512070329, "y": 40.09287269670172, "z": 202.52206396905402, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.563942816221561, "steering_wheel_angle": -0.083, "front_wheel_angle": -0.003815863845306958, "heading_rate": -0.011701045536713896, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059834.829418}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.083, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059834.829418}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059834.9295769, "x": -88.23535512070329, "y": 40.09287269670172, "z": 202.52206396905402, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": -0.116, "front_wheel_angle": -0.005335329359043072, "heading_rate": -0.016714745107120715, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059834.9294522}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.116, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059834.9294522}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059835.029936, "x": -88.23535512070329, "y": 40.09287269670172, "z": 202.52206396905402, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": -0.116, "front_wheel_angle": -0.005335329359043072, "heading_rate": -0.01688147573163065, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059835.0295055}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.116, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059835.0295055}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059835.1296253, "x": -88.23540103940569, "y": 40.09287223857123, "z": 202.507596190724, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": -0.111, "front_wheel_angle": -0.005105022404758634, "heading_rate": -0.015993216937077604, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059835.1294658}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.111, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059835.1294658}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059835.2295575, "x": -88.23540103940569, "y": 40.09287223857123, "z": 202.507596190724, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.650493816221561, "steering_wheel_angle": -0.1, "front_wheel_angle": -0.004598453893036984, "heading_rate": -0.01483730347150904, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059835.2294455}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.26, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059835.2294455}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059835.3295825, "x": -88.23540103940569, "y": 40.09287223857123, "z": 202.507596190724, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.650493816221561, "steering_wheel_angle": -0.08, "front_wheel_angle": -0.003677796062834341, "heading_rate": -0.011866692362724822, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059835.3294477}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.26, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.08, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059835.3294477}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059835.4295034, "x": -88.23540103940569, "y": 40.09287223857123, "z": 202.507596190724, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.667773816221562, "steering_wheel_angle": -0.047, "front_wheel_angle": -0.0021597690564398976, "heading_rate": -0.007036133569441631, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059835.4294105}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.047, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059835.4294105}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059835.5295978, "x": -88.23540103940569, "y": 40.09287223857123, "z": 202.507596190724, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.687366816221561, "steering_wheel_angle": -0.013, "front_wheel_angle": -0.0005971166232941916, "heading_rate": -0.0019662866143053256, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059835.5294313}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059835.5294313}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059835.6295373, "x": -88.23544933915997, "y": 40.09287208128722, "z": 202.51587157960478, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.704918816221562, "steering_wheel_angle": 0.007, "front_wheel_angle": 0.00032149905694411315, "heading_rate": 0.0010687332300229465, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059835.6294186}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.51, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.007, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059835.6294186}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059835.7295775, "x": -88.23544933915997, "y": 40.09287208128722, "z": 202.51587157960478, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.722598816221561, "steering_wheel_angle": 0.004, "front_wheel_angle": 0.00018370652604977013, "heading_rate": 0.0006164215142654137, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059835.7294507}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.59, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.004, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059835.7294507}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059835.8296335, "x": -88.23544933915997, "y": 40.09287208128722, "z": 202.51587157960478, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.722598816221561, "steering_wheel_angle": -0.049, "front_wheel_angle": -0.002251733223960032, "heading_rate": -0.007555633236121013, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059835.829445}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.59, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.049, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059835.829445}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059835.9298184, "x": -88.23544933915997, "y": 40.09287208128722, "z": 202.51587157960478, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.740406816221562, "steering_wheel_angle": -0.138, "front_wheel_angle": -0.006349040727595683, "heading_rate": -0.021502704204387657, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059835.929498}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.138, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059835.929498}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059836.0295472, "x": -88.23544933915997, "y": 40.09287208128722, "z": 202.51587157960478, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.758342816221561, "steering_wheel_angle": -0.23, "front_wheel_angle": -0.010594587371297717, "heading_rate": -0.036213323489276465, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059836.0294235}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.75, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.23, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059836.0294235}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059836.1295369, "x": -88.23549954963713, "y": 40.09287195033314, "z": 202.4973655824925, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.776406816221561, "steering_wheel_angle": -0.287, "front_wheel_angle": -0.013230178396903713, "heading_rate": -0.04563644212159494, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059836.129444}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.287, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059836.129444}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059836.229511, "x": -88.23549954963713, "y": 40.09287195033314, "z": 202.4973655824925, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.796881816221561, "steering_wheel_angle": -0.298, "front_wheel_angle": -0.01373926097338927, "heading_rate": -0.04787574995062256, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059836.2294111}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.298, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059836.2294111}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059836.3295093, "x": -88.23549954963713, "y": 40.09287195033314, "z": 202.4973655824925, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.796881816221561, "steering_wheel_angle": -0.344, "front_wheel_angle": -0.015869768215077257, "heading_rate": -0.05530086620165626, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059836.329412}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.344, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059836.329412}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059836.4295883, "x": -88.23549954963713, "y": 40.09287195033314, "z": 202.4973655824925, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.815217816221562, "steering_wheel_angle": -0.449, "front_wheel_angle": -0.02074269956941707, "heading_rate": -0.07293401365994416, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059836.429421}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.449, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059836.429421}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059836.5295372, "x": -88.23549954963713, "y": 40.09287195033314, "z": 202.4973655824925, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.815217816221562, "steering_wheel_angle": -0.49, "front_wheel_angle": -0.022649188700333035, "heading_rate": -0.07963967249603002, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059836.5294192}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.49, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059836.5294192}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059836.6295586, "x": -88.23555201246928, "y": 40.09287265177099, "z": 202.4361838263686, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.852273816221562, "steering_wheel_angle": -0.4, "front_wheel_angle": -0.01846696129099199, "heading_rate": -0.06608460828858459, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059836.6294487}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059836.6294487}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059836.729659, "x": -88.23555201246928, "y": 40.09287265177099, "z": 202.4361838263686, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.852273816221562, "steering_wheel_angle": -0.248, "front_wheel_angle": -0.011426448373243307, "heading_rate": -0.04088704005571644, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059836.7294867}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.248, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059836.7294867}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059836.8296947, "x": -88.23555201246928, "y": 40.09287265177099, "z": 202.4361838263686, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.870993816221562, "steering_wheel_angle": -0.059, "front_wheel_angle": -0.002711626542631913, "heading_rate": -0.009787301040732804, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059836.829445}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.059, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059836.829445}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059836.929505, "x": -88.23555201246928, "y": 40.09287265177099, "z": 202.4361838263686, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": 0.145, "front_wheel_angle": 0.006671708657912529, "heading_rate": 0.024315611472100367, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059836.9294095}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.145, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059836.9294095}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059837.0295174, "x": -88.23555201246928, "y": 40.09287265177099, "z": 202.4361838263686, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": 0.247, "front_wheel_angle": 0.011380223449293793, "heading_rate": 0.041477370579372015, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059837.0294118}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.247, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059837.0294118}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059837.129543, "x": -88.2356056686585, "y": 40.09287448455305, "z": 202.41765821980542, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.911198816221562, "steering_wheel_angle": 0.232, "front_wheel_angle": 0.010686996757971879, "heading_rate": 0.03928455790114719, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059837.129423}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.232, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059837.129423}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059837.2295337, "x": -88.2356056686585, "y": 40.09287448455305, "z": 202.41765821980542, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.911198816221562, "steering_wheel_angle": 0.195, "front_wheel_angle": 0.008978215725623, "heading_rate": 0.033002843795810616, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059837.2294164}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.195, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059837.2294164}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059837.3302498, "x": -88.2356056686585, "y": 40.09287448455305, "z": 202.41765821980542, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.930318816221561, "steering_wheel_angle": 0.176, "front_wheel_angle": 0.008101383877872934, "heading_rate": 0.030032740246877295, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059837.329979}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.49, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.176, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059837.329979}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059837.4296477, "x": -88.2356056686585, "y": 40.09287448455305, "z": 202.41765821980542, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.911198816221562, "steering_wheel_angle": 0.202, "front_wheel_angle": 0.009301370185803915, "heading_rate": 0.03419078814487367, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059837.4294333}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.202, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059837.4294333}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059837.5299234, "x": -88.2356056686585, "y": 40.09287448455305, "z": 202.41765821980542, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.930318816221561, "steering_wheel_angle": 0.273, "front_wheel_angle": 0.01258247048583879, "heading_rate": 0.04664607296561112, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059837.5294178}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.49, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059837.5294178}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059837.6294758, "x": -88.23566050643917, "y": 40.09287566365, "z": 202.42251495949694, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.930318816221561, "steering_wheel_angle": 0.383, "front_wheel_angle": 0.01767811677342035, "heading_rate": 0.06554015890780915, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059837.6293597}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.49, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.383, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059837.6293597}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059837.7295127, "x": -88.23566050643917, "y": 40.09287566365, "z": 202.42251495949694, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.949566816221562, "steering_wheel_angle": 0.506, "front_wheel_angle": 0.02339375452353141, "heading_rate": 0.0874683906944162, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059837.729413}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.506, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059837.729413}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059837.829498, "x": -88.23566050643917, "y": 40.09287566365, "z": 202.42251495949694, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.010541816221561, "steering_wheel_angle": 0.62, "front_wheel_angle": 0.028708092339196797, "heading_rate": 0.11015271057328152, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059837.8294106}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.62, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059837.8294106}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059837.9296477, "x": -88.23566050643917, "y": 40.09287566365, "z": 202.42251495949694, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.990893816221561, "steering_wheel_angle": 0.71, "front_wheel_angle": 0.032915220264261434, "heading_rate": 0.12527737269207617, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059837.9294777}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.71, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059837.9294777}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059838.0296104, "x": -88.23566050643917, "y": 40.09287566365, "z": 202.42251495949694, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.990893816221561, "steering_wheel_angle": 0.774, "front_wheel_angle": 0.0359132271550315, "heading_rate": 0.1366973804277564, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059838.029436}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.774, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059838.029436}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059838.1300383, "x": -88.2357159989965, "y": 40.092875043171446, "z": 202.40640042519146, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.010541816221561, "steering_wheel_angle": 0.803, "front_wheel_angle": 0.03727342372813372, "heading_rate": 0.14304477439056806, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059838.1297324}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.803, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059838.1297324}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059838.2296486, "x": -88.2357159989965, "y": 40.092875043171446, "z": 202.40640042519146, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.010541816221561, "steering_wheel_angle": 0.806, "front_wheel_angle": 0.0374141952704206, "heading_rate": 0.14358551897980618, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059838.2294524}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.806, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059838.2294524}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059838.329576, "x": -88.2357159989965, "y": 40.092875043171446, "z": 202.40640042519146, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.050221816221562, "steering_wheel_angle": 0.8, "front_wheel_angle": 0.037132663735044605, "heading_rate": 0.14482593857637718, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059838.32945}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.8, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059838.32945}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059838.4295511, "x": -88.2357159989965, "y": 40.092875043171446, "z": 202.40640042519146, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.030317816221562, "steering_wheel_angle": 0.798, "front_wheel_angle": 0.037038830154469154, "heading_rate": 0.14330163762389375, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059838.4294217}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.9, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.798, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059838.4294217}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059838.5296175, "x": -88.2357159989965, "y": 40.092875043171446, "z": 202.40640042519146, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.050221816221562, "steering_wheel_angle": 0.78, "front_wheel_angle": 0.0361945587175771, "heading_rate": 0.14116387411164272, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059838.5294416}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.78, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059838.5294416}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059838.6294904, "x": -88.23577186297456, "y": 40.09287143876871, "z": 202.38306222774423, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.050221816221562, "steering_wheel_angle": 0.718, "front_wheel_angle": 0.03328968529822271, "heading_rate": 0.12982571883002725, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059838.6294065}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.718, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059838.6294065}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059838.7295392, "x": -88.23577186297456, "y": 40.09287143876871, "z": 202.38306222774423, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.070253816221562, "steering_wheel_angle": 0.628, "front_wheel_angle": 0.029081643499481183, "heading_rate": 0.11431399947296052, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059838.7294443}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.628, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059838.7294443}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059838.8295617, "x": -88.23577186297456, "y": 40.09287143876871, "z": 202.38306222774423, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.070253816221562, "steering_wheel_angle": 0.493, "front_wheel_angle": 0.022788770385573053, "heading_rate": 0.08956825176341196, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059838.829455}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.493, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059838.829455}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059838.9298012, "x": -88.23577186297456, "y": 40.09287143876871, "z": 202.38306222774423, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.090413816221561, "steering_wheel_angle": 0.354, "front_wheel_angle": 0.016333267821078794, "heading_rate": 0.06470080664536822, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059838.9294624}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.14, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.354, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059838.9294624}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059839.0296047, "x": -88.23577186297456, "y": 40.09287143876871, "z": 202.38306222774423, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.090413816221561, "steering_wheel_angle": 0.22, "front_wheel_angle": 0.010132613934107136, "heading_rate": 0.0401360241007565, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059839.0294714}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.14, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.22, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059839.0294714}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059839.129552, "x": -88.23582892079273, "y": 40.092864286011405, "z": 202.33936314954218, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.113246816221562, "steering_wheel_angle": 0.06, "front_wheel_angle": 0.0027576225208671363, "heading_rate": 0.011019746053663954, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059839.1294167}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.06, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059839.1294167}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059839.2295272, "x": -88.23582892079273, "y": 40.092864286011405, "z": 202.33936314954218, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.113246816221562, "steering_wheel_angle": -0.117, "front_wheel_angle": -0.005381394392021079, "heading_rate": -0.021504764085036435, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059839.2294166}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.117, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059839.2294166}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059839.3295205, "x": -88.23582892079273, "y": 40.092864286011405, "z": 202.33936314954218, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.113246816221562, "steering_wheel_angle": -0.28, "front_wheel_angle": -0.012906294304269457, "heading_rate": -0.05157762584029016, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059839.329412}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.28, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059839.329412}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059839.429499, "x": -88.23582892079273, "y": 40.092864286011405, "z": 202.33936314954218, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.090413816221561, "steering_wheel_angle": -0.416, "front_wheel_angle": -0.01920973105712699, "heading_rate": -0.07609790473087372, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059839.4294083}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.14, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059839.4294083}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059839.5295112, "x": -88.23582892079273, "y": 40.092864286011405, "z": 202.33936314954218, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.113246816221562, "steering_wheel_angle": -0.522, "front_wheel_angle": -0.024138641011854586, "heading_rate": -0.09647901181249074, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059839.529408}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.522, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059839.529408}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059839.6295197, "x": -88.23588746372248, "y": 40.09285595333328, "z": 202.3600548992812, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.070253816221562, "steering_wheel_angle": -0.522, "front_wheel_angle": -0.024138641011854586, "heading_rate": -0.09487574377650605, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059839.6294112}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.522, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059839.6294112}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059839.7295444, "x": -88.23588746372248, "y": 40.09285595333328, "z": 202.3600548992812, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.050221816221562, "steering_wheel_angle": -0.585, "front_wheel_angle": -0.027074756640425458, "heading_rate": -0.10557504484759347, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059839.7294168}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.585, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059839.7294168}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059839.8295324, "x": -88.23588746372248, "y": 40.09285595333328, "z": 202.3600548992812, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.050221816221562, "steering_wheel_angle": -0.602, "front_wheel_angle": -0.02786789797492743, "heading_rate": -0.10866939156636152, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059839.8294117}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.602, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059839.8294117}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059839.9295378, "x": -88.23588746372248, "y": 40.09285595333328, "z": 202.3600548992812, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.090413816221561, "steering_wheel_angle": -0.597, "front_wheel_angle": -0.02763458326328851, "heading_rate": -0.10948672914729207, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059839.9294167}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.14, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.597, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059839.9294167}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059840.02954, "x": -88.23588746372248, "y": 40.09285595333328, "z": 202.3600548992812, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.050221816221562, "steering_wheel_angle": -0.597, "front_wheel_angle": -0.02763458326328851, "heading_rate": -0.10775912789841961, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059840.0294173}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.597, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059840.0294173}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059840.1295125, "x": -88.23594618119435, "y": 40.092850042581716, "z": 202.36142417525588, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.990893816221561, "steering_wheel_angle": -0.613, "front_wheel_angle": -0.028381301447057847, "heading_rate": -0.10801098529414768, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059840.129409}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.613, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059840.129409}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059840.229524, "x": -88.23594618119435, "y": 40.092850042581716, "z": 202.36142417525588, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.911198816221562, "steering_wheel_angle": -0.639, "front_wheel_angle": -0.029595408552037412, "heading_rate": -0.1088180205039712, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059840.2294087}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.639, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059840.2294087}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059840.3296025, "x": -88.23594618119435, "y": 40.092850042581716, "z": 202.36142417525588, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.949566816221562, "steering_wheel_angle": -0.641, "front_wheel_angle": -0.02968883683595946, "heading_rate": -0.11101784203739266, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059840.3294349}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.641, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059840.3294349}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059840.4295993, "x": -88.23594618119435, "y": 40.092850042581716, "z": 202.36142417525588, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.815217816221562, "steering_wheel_angle": -0.584, "front_wheel_angle": -0.027028112618382952, "heading_rate": -0.09504385332737729, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059840.4294236}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.584, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059840.4294236}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059840.5296035, "x": -88.23594618119435, "y": 40.092850042581716, "z": 202.36142417525588, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.833681816221562, "steering_wheel_angle": -0.457, "front_wheel_angle": -0.02111453264700293, "heading_rate": -0.07490173929809575, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059840.5294275}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.457, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059840.5294275}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059840.6295233, "x": -88.23600137574084, "y": 40.09284764684353, "z": 202.365624308038, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.722598816221561, "steering_wheel_angle": -0.263, "front_wheel_angle": -0.012119969521549536, "heading_rate": -0.04067017039675754, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059840.6294103}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.59, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.263, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059840.6294103}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059840.7298782, "x": -88.23600137574084, "y": 40.09284764684353, "z": 202.365624308038, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.704918816221562, "steering_wheel_angle": -0.008, "front_wheel_angle": -0.00036743230800517036, "heading_rate": -0.0012214254225933537, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059840.729456}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.51, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.008, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059840.729456}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059840.8295188, "x": -88.23600137574084, "y": 40.09284764684353, "z": 202.365624308038, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": 0.304, "front_wheel_angle": 0.014017005194941706, "heading_rate": 0.04435358534910697, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059840.8294098}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.304, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059840.8294098}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059840.9296865, "x": -88.23600137574084, "y": 40.09284764684353, "z": 202.365624308038, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": 0.703, "front_wheel_angle": 0.03258763022088541, "heading_rate": 0.10212708927254936, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059840.9294295}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.703, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059840.9294295}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059841.0295348, "x": -88.23600137574084, "y": 40.09284764684353, "z": 202.365624308038, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.514838816221562, "steering_wheel_angle": 1.205, "front_wheel_angle": 0.05624088110541183, "heading_rate": 0.16736130058970589, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059841.0294394}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.205, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059841.0294394}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059841.129536, "x": -88.23604879633042, "y": 40.092845756694125, "z": 202.3154717234049, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.449201816221562, "steering_wheel_angle": 1.757, "front_wheel_angle": 0.08263663954053146, "heading_rate": 0.23553432798637552, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059841.1294055}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.757, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059841.1294055}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059841.2295945, "x": -88.23604879633042, "y": 40.092845756694125, "z": 202.3154717234049, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": 2.225, "front_wheel_angle": 0.10534686159995135, "heading_rate": 0.29738900026338894, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059841.2294142}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.225, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059841.2294142}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059841.3295186, "x": -88.23604879633042, "y": 40.092845756694125, "z": 202.3154717234049, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": 2.599, "front_wheel_angle": 0.12372318341260312, "heading_rate": 0.33761353651053905, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059841.32941}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.599, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059841.32941}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059841.4295168, "x": -88.23604879633042, "y": 40.092845756694125, "z": 202.3154717234049, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": 3.009, "front_wheel_angle": 0.1441095011265176, "heading_rate": 0.3894309382801517, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059841.429408}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.009, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059841.429408}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059841.5295317, "x": -88.23604879633042, "y": 40.092845756694125, "z": 202.3154717234049, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3099338162215615, "steering_wheel_angle": 3.44, "front_wheel_angle": 0.1658222859054093, "heading_rate": 0.42755010968952184, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059841.529412}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.54, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.44, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059841.529412}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059841.6296222, "x": -88.23608769396408, "y": 40.09284002422338, "z": 202.25018446016404, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": 3.771, "front_wheel_angle": 0.18270111150509796, "heading_rate": 0.4662339999654122, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059841.6295269}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.771, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059841.6295269}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059841.7295232, "x": -88.23608769396408, "y": 40.09284002422338, "z": 202.25018446016404, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": 4.202, "front_wheel_angle": 0.20495509328013703, "heading_rate": 0.5180609082764784, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059841.7294312}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.202, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059841.7294312}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059841.829592, "x": -88.23608769396408, "y": 40.09284002422338, "z": 202.25018446016404, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.237486816221562, "steering_wheel_angle": 4.741, "front_wheel_angle": 0.23324399914711957, "heading_rate": 0.5688635707350803, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059841.829421}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.741, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059841.829421}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059841.9295132, "x": -88.23608769396408, "y": 40.09284002422338, "z": 202.25018446016404, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.223742816221561, "steering_wheel_angle": 5.218, "front_wheel_angle": 0.2587255239236083, "heading_rate": 0.6254597198280527, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059841.9294083}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.218, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059841.9294083}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059842.0296383, "x": -88.23608769396408, "y": 40.09284002422338, "z": 202.25018446016404, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1966388162215615, "steering_wheel_angle": 5.588, "front_wheel_angle": 0.278794367801537, "heading_rate": 0.6585973779423807, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059842.0294585}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.588, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059842.0294585}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059842.1295168, "x": -88.23608769396408, "y": 40.09284002422338, "z": 202.25018446016404, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": 5.801, "front_wheel_angle": 0.2904724076430024, "heading_rate": 0.6679157636463298, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059842.1294084}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.801, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059842.1294084}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059842.2295263, "x": -88.23608769396408, "y": 40.09284002422338, "z": 202.25018446016404, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": 5.941, "front_wheel_angle": 0.2981991708537388, "heading_rate": 0.6771617476142457, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059842.229409}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.941, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059842.229409}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059842.329532, "x": -88.23611831554979, "y": 40.092828624630556, "z": 202.20995860474713, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.142353816221561, "steering_wheel_angle": 6.111, "front_wheel_angle": 0.30763720079426526, "heading_rate": 0.6900573016680609, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059842.3294084}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.111, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059842.3294084}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059842.429528, "x": -88.23611831554979, "y": 40.092828624630556, "z": 202.20995860474713, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1966388162215615, "steering_wheel_angle": 6.283, "front_wheel_angle": 0.31724940684615777, "heading_rate": 0.7554374047760163, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059842.4294076}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.283, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059842.4294076}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059842.5295093, "x": -88.23611831554979, "y": 40.092828624630556, "z": 202.20995860474713, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": 6.449, "front_wheel_angle": 0.32658772717099044, "heading_rate": 0.7462352116543498, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059842.5294092}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.449, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059842.5294092}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059842.629528, "x": -88.23613919206997, "y": 40.092812638146995, "z": 202.22123567827003, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": 6.654, "front_wheel_angle": 0.33820504908966215, "heading_rate": 0.7528976380444959, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059842.6294055}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.654, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059842.6294055}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059842.7295501, "x": -88.23613919206997, "y": 40.092812638146995, "z": 202.22123567827003, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": 6.874, "front_wheel_angle": 0.35077948706045686, "heading_rate": 0.7718458293226765, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059842.7294395}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.874, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059842.7294395}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059842.8301184, "x": -88.23613919206997, "y": 40.092812638146995, "z": 202.22123567827003, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": 7.164, "front_wheel_angle": 0.3675292448141875, "heading_rate": 0.7986228114677484, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059842.829488}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.164, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059842.829488}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059842.9295094, "x": -88.23613919206997, "y": 40.092812638146995, "z": 202.22123567827003, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": 7.405, "front_wheel_angle": 0.3816045115472988, "heading_rate": 0.8197910516937357, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059842.9294066}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.405, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059842.9294066}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059843.0295184, "x": -88.23613919206997, "y": 40.092812638146995, "z": 202.22123567827003, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": 7.583, "front_wheel_angle": 0.39209381636161694, "heading_rate": 0.8447770321092718, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059843.029411}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.583, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059843.029411}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059843.1296258, "x": -88.2361502663579, "y": 40.09279336413992, "z": 202.24420969014588, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": 7.701, "front_wheel_angle": 0.3990921932493567, "heading_rate": 0.8483891689586256, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059843.129445}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.701, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059843.129445}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059843.2297714, "x": -88.2361502663579, "y": 40.09279336413992, "z": 202.24420969014588, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": 7.8, "front_wheel_angle": 0.4049917417296252, "heading_rate": 0.8490066498509897, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059843.2296598}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.8, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059843.2296598}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059843.3295045, "x": -88.2361502663579, "y": 40.09279336413992, "z": 202.24420969014588, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": 7.983, "front_wheel_angle": 0.4159654993352593, "heading_rate": 0.8610520499269693, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059843.3294063}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.983, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059843.3294063}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059843.4296036, "x": -88.2361502663579, "y": 40.09279336413992, "z": 202.24420969014588, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": 8.197, "front_wheel_angle": 0.42891355943932413, "heading_rate": 0.8771000033236708, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059843.429516}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.197, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059843.429516}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059843.5295017, "x": -88.2361502663579, "y": 40.09279336413992, "z": 202.24420969014588, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": 8.425, "front_wheel_angle": 0.44284947896948323, "heading_rate": 0.8929543936558825, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059843.5294046}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.425, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059843.5294046}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059843.6295118, "x": -88.23615108822284, "y": 40.09277366754933, "z": 202.2338378493197, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": 8.687, "front_wheel_angle": 0.45904888422237206, "heading_rate": 0.8997162864159806, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059843.6294067}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.687, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059843.6294067}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059843.7295446, "x": -88.23615108822284, "y": 40.09277366754933, "z": 202.2338378493197, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": 8.936, "front_wheel_angle": 0.474634744147109, "heading_rate": 0.9352953894519518, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059843.7294154}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.936, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059843.7294154}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059843.82951, "x": -88.23615108822284, "y": 40.09277366754933, "z": 202.2338378493197, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": 9.054, "front_wheel_angle": 0.4820875659147225, "heading_rate": 0.9361575561151537, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059843.829409}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.054, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059843.829409}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059843.9295132, "x": -88.23615108822284, "y": 40.09277366754933, "z": 202.2338378493197, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": 9.082, "front_wheel_angle": 0.48386245684901796, "heading_rate": 0.9053076782400714, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059843.9294088}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.082, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059843.9294088}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059844.0295422, "x": -88.23615108822284, "y": 40.09277366754933, "z": 202.2338378493197, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9592068162215615, "steering_wheel_angle": 9.159, "front_wheel_angle": 0.48875625540977696, "heading_rate": 0.899475655222284, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059844.0294125}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.159, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059844.0294125}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059844.1297421, "x": -88.23614302789738, "y": 40.09275730151096, "z": 202.2092340767785, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9483428162215617, "steering_wheel_angle": 9.281, "front_wheel_angle": 0.4965490916877935, "heading_rate": 0.8995226006177012, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059844.1294217}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.25, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.281, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059844.1294217}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059844.2295015, "x": -88.23614302789738, "y": 40.09275730151096, "z": 202.2092340767785, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9376068162215616, "steering_wheel_angle": 9.413, "front_wheel_angle": 0.5050354932049059, "heading_rate": 0.9005553165663273, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059844.2294037}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.17, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.413, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059844.2294037}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059844.3295991, "x": -88.23614302789738, "y": 40.09275730151096, "z": 202.2092340767785, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9269988162215617, "steering_wheel_angle": 9.573, "front_wheel_angle": 0.5154000569473602, "heading_rate": 0.9050241811201237, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059844.3294208}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.09, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.573, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059844.3294208}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059844.4297411, "x": -88.23614302789738, "y": 40.09275730151096, "z": 202.2092340767785, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9010388162215617, "steering_wheel_angle": 9.711, "front_wheel_angle": 0.5244097221026868, "heading_rate": 0.8789455576159569, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059844.429459}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.711, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059844.429459}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059844.5295267, "x": -88.23614302789738, "y": 40.09275730151096, "z": 202.2092340767785, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8921418162215615, "steering_wheel_angle": 9.782, "front_wheel_angle": 0.5290709688563228, "heading_rate": 0.8724368549932644, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059844.5294087}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.782, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059844.5294087}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059844.6295183, "x": -88.23612968546892, "y": 40.092746438297226, "z": 202.2326121755564, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8709428162215618, "steering_wheel_angle": 9.836, "front_wheel_angle": 0.5326280624110104, "heading_rate": 0.8404306617191537, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059844.6294057}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.836, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059844.6294057}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059844.729531, "x": -88.23612968546892, "y": 40.092746438297226, "z": 202.2326121755564, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8635988162215615, "steering_wheel_angle": 9.916, "front_wheel_angle": 0.5379169717290326, "heading_rate": 0.836640604596818, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059844.7294173}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.59, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.916, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059844.7294173}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059844.8295443, "x": -88.23612968546892, "y": 40.092746438297226, "z": 202.2326121755564, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8771178162215616, "steering_wheel_angle": 10.003, "front_wheel_angle": 0.543694916433882, "heading_rate": 0.8736384406745299, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059844.8294141}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.7, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.003, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059844.8294141}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059844.9296548, "x": -88.23612968546892, "y": 40.092746438297226, "z": 202.2326121755564, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8539188162215616, "steering_wheel_angle": 10.036, "front_wheel_angle": 0.5458937855714419, "heading_rate": 0.8328978228529842, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059844.929474}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.51, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.036, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059844.929474}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059845.0294921, "x": -88.23612968546892, "y": 40.092746438297226, "z": 202.2326121755564, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8503218162215616, "steering_wheel_angle": 10.035, "front_wheel_angle": 0.5458270943256164, "heading_rate": 0.8256549299484847, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059845.0294027}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.035, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059845.0294027}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059845.129558, "x": -88.23611463178185, "y": 40.092740770779365, "z": 202.2422548088315, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8443668162215614, "steering_wheel_angle": 10.032, "front_wheel_angle": 0.5456270426913665, "heading_rate": 0.8134251969435455, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059845.1294029}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.032, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059845.1294029}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059845.2295227, "x": -88.23611463178185, "y": 40.092740770779365, "z": 202.2422548088315, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8302788162215617, "steering_wheel_angle": 9.998, "front_wheel_angle": 0.5433621031395729, "heading_rate": 0.7809648000713335, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059845.2294037}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059845.2294037}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059845.3295426, "x": -88.23611463178185, "y": 40.092740770779365, "z": 202.2422548088315, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8256468162215613, "steering_wheel_angle": 9.9, "front_wheel_angle": 0.5368573497451972, "heading_rate": 0.7602312981810612, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059845.3294077}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.27, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.9, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059845.3294077}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059845.4295251, "x": -88.23611463178185, "y": 40.092740770779365, "z": 202.2422548088315, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8337738162215613, "steering_wheel_angle": 9.737, "front_wheel_angle": 0.5261146023633027, "heading_rate": 0.7576445450608313, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059845.4294057}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.737, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059845.4294057}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059845.529522, "x": -88.23611463178185, "y": 40.092740770779365, "z": 202.2422548088315, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8007428162215615, "steering_wheel_angle": 9.479, "front_wheel_angle": 0.5093004093276757, "heading_rate": 0.6653296147248523, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059845.5294087}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.479, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059845.5294087}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059845.6296346, "x": -88.23609944696308, "y": 40.092739495144244, "z": 202.24784047420331, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8164788162215615, "steering_wheel_angle": 8.903, "front_wheel_angle": 0.4725582426346963, "heading_rate": 0.636988715408865, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059845.629438}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.19, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.903, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059845.629438}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059845.7295125, "x": -88.23609944696308, "y": 40.092739495144244, "z": 202.24784047420331, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7952178162215615, "steering_wheel_angle": 8.033, "front_wheel_angle": 0.41897949546958213, "heading_rate": 0.5218934562899843, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059845.7294188}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.033, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059845.7294188}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059845.8295105, "x": -88.23609944696308, "y": 40.092739495144244, "z": 202.24784047420331, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8096868162215616, "steering_wheel_angle": 7.154, "front_wheel_angle": 0.3669482973682901, "heading_rate": 0.46993588580168694, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059845.8294137}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.154, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059845.8294137}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059845.9296463, "x": -88.23609944696308, "y": 40.092739495144244, "z": 202.24784047420331, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7952178162215615, "steering_wheel_angle": 6.327, "front_wheel_angle": 0.3197186980277016, "heading_rate": 0.38798114069539136, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059845.9294388}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059845.9294388}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059846.0295846, "x": -88.23609944696308, "y": 40.092739495144244, "z": 202.24784047420331, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8085618162215615, "steering_wheel_angle": 5.551, "front_wheel_angle": 0.27677520582002924, "heading_rate": 0.3462055642174585, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059846.0294194}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.551, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059846.0294194}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059846.129602, "x": -88.2360835351832, "y": 40.09274021896929, "z": 202.23678705003886, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8164788162215615, "steering_wheel_angle": 4.868, "front_wheel_angle": 0.2399864679257434, "heading_rate": 0.3049220817829733, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059846.1294208}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.19, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.868, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059846.1294208}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059846.229553, "x": -88.2360835351832, "y": 40.09274021896929, "z": 202.23678705003886, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.822193816221562, "steering_wheel_angle": 4.324, "front_wheel_angle": 0.21131269769310818, "heading_rate": 0.27149575241715973, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059846.229407}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.324, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059846.229407}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059846.329537, "x": -88.2360835351832, "y": 40.09274021896929, "z": 202.23678705003886, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8326068162215616, "steering_wheel_angle": 3.995, "front_wheel_angle": 0.19422733280986443, "heading_rate": 0.2558729326303025, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059846.3294067}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.995, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059846.3294067}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059846.4295104, "x": -88.2360835351832, "y": 40.09274021896929, "z": 202.23678705003886, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8337738162215613, "steering_wheel_angle": 4.013, "front_wheel_angle": 0.19515724886475974, "heading_rate": 0.25790174570475344, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059846.4294012}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059846.4294012}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059846.529516, "x": -88.2360835351832, "y": 40.09274021896929, "z": 202.23678705003886, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8623818162215615, "steering_wheel_angle": 4.221, "front_wheel_angle": 0.20594349437400286, "heading_rate": 0.2921409959225079, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059846.5294037}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.221, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059846.5294037}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059846.62949, "x": -88.23606543965231, "y": 40.0927413034228, "z": 202.2415124138546, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8491268162215615, "steering_wheel_angle": 4.609, "front_wheel_angle": 0.22626763711614772, "heading_rate": 0.31204218851285603, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059846.6293993}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.47, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.609, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059846.6293993}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059846.7295024, "x": -88.23606543965231, "y": 40.0927413034228, "z": 202.2415124138546, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8858468162215614, "steering_wheel_angle": 5.101, "front_wheel_angle": 0.25243528605631077, "heading_rate": 0.3798534274536632, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059846.7294035}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.101, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059846.7294035}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059846.8297184, "x": -88.23606543965231, "y": 40.0927413034228, "z": 202.2415124138546, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8820938162215617, "steering_wheel_angle": 5.623, "front_wheel_angle": 0.2807069346085766, "heading_rate": 0.4212173111712546, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059846.8294325}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.623, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059846.8294325}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059846.929564, "x": -88.23606543965231, "y": 40.0927413034228, "z": 202.2415124138546, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8984868162215616, "steering_wheel_angle": 6.033, "front_wheel_angle": 0.3032991819501508, "heading_rate": 0.4730996886466392, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059846.9294105}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.033, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059846.9294105}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059847.0294988, "x": -88.23606543965231, "y": 40.0927413034228, "z": 202.2415124138546, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.919126816221562, "steering_wheel_angle": 6.318, "front_wheel_angle": 0.3192132697675454, "heading_rate": 0.5203052785851122, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059847.0294018}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.318, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059847.0294018}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059847.1295013, "x": -88.23604605747765, "y": 40.09274514103985, "z": 202.25316488177566, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.919126816221562, "steering_wheel_angle": 6.44, "front_wheel_angle": 0.326079865796367, "heading_rate": 0.5323231113974616, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059847.129405}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.44, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059847.129405}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059847.229677, "x": -88.23604605747765, "y": 40.09274514103985, "z": 202.25316488177566, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9283178162215613, "steering_wheel_angle": 6.449, "front_wheel_angle": 0.32658772717099044, "heading_rate": 0.5424759517345451, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059847.2294188}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.449, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059847.2294188}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059847.3295155, "x": -88.23604605747765, "y": 40.09274514103985, "z": 202.25316488177566, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9429588162215614, "steering_wheel_angle": 6.421, "front_wheel_angle": 0.32500830716045426, "heading_rate": 0.5541363270235655, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059847.3294036}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.21, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.421, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059847.3294036}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059847.4294832, "x": -88.23604605747765, "y": 40.09274514103985, "z": 202.25316488177566, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9564788162215616, "steering_wheel_angle": 6.258, "front_wheel_angle": 0.3158482906695425, "heading_rate": 0.5501783418258375, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059847.4293978}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.258, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059847.4293978}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059847.5294986, "x": -88.23604605747765, "y": 40.09274514103985, "z": 202.25316488177566, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9715818162215615, "steering_wheel_angle": 5.811, "front_wheel_angle": 0.2910229649882705, "heading_rate": 0.5171524094309063, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059847.5294003}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.42, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.811, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059847.5294003}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059847.6295424, "x": -88.23602689415905, "y": 40.09275342337459, "z": 202.2169626031015, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9855218162215618, "steering_wheel_angle": 4.978, "front_wheel_angle": 0.24585077896510826, "heading_rate": 0.4430426760754865, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059847.629412}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.978, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059847.629412}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059847.729541, "x": -88.23602689415905, "y": 40.09275342337459, "z": 202.2169626031015, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.003942816221562, "steering_wheel_angle": 3.972, "front_wheel_angle": 0.19303991344879642, "heading_rate": 0.35506027126714645, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059847.729416}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.972, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059847.729416}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059847.8298023, "x": -88.23602689415905, "y": 40.09275342337459, "z": 202.2169626031015, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9996618162215616, "steering_wheel_angle": 3.046, "front_wheel_angle": 0.14596196434565567, "heading_rate": 0.26530249458057265, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059847.8294373}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.046, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059847.8294373}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059847.9295313, "x": -88.23602689415905, "y": 40.09275342337459, "z": 202.2169626031015, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": 2.237, "front_wheel_angle": 0.10593329252619935, "heading_rate": 0.19687911360037444, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059847.92942}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.237, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059847.92942}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059848.0295348, "x": -88.23602689415905, "y": 40.09275342337459, "z": 202.2169626031015, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.037361816221561, "steering_wheel_angle": 1.433, "front_wheel_angle": 0.06709337916158235, "heading_rate": 0.12808901020950184, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059848.0294328}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.88, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.433, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059848.0294328}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059848.1295285, "x": -88.23600580600669, "y": 40.092765204184126, "z": 202.24269780243563, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": 0.631, "front_wheel_angle": 0.029221746054878917, "heading_rate": 0.05697579364958685, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059848.1294272}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.631, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059848.1294272}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059848.229521, "x": -88.23600580600669, "y": 40.092765204184126, "z": 202.24269780243563, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": -0.145, "front_wheel_angle": -0.006671708657912529, "heading_rate": -0.01342180054462132, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059848.229428}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.145, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059848.229428}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059848.329549, "x": -88.23600580600669, "y": 40.092765204184126, "z": 202.24269780243563, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": -0.872, "front_wheel_angle": -0.040514096914930235, "heading_rate": -0.08154759047500129, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059848.3294382}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.872, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059848.3294382}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059848.429607, "x": -88.23600580600669, "y": 40.092765204184126, "z": 202.24269780243563, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": -1.566, "front_wheel_angle": -0.07345638691832995, "heading_rate": -0.15522635887835767, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059848.4294293}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.566, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059848.4294293}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059848.529529, "x": -88.23600580600669, "y": 40.092765204184126, "z": 202.24269780243563, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": -2.258, "front_wheel_angle": -0.10696004938323221, "heading_rate": -0.2264832037059735, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059848.5294082}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.258, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059848.5294082}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059848.6295455, "x": -88.23598025952114, "y": 40.09277821103967, "z": 202.25459024857673, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.142353816221561, "steering_wheel_angle": -2.91, "front_wheel_angle": -0.13916336681919209, "heading_rate": -0.3042118110260334, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059848.6294265}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.91, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059848.6294265}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059848.7295146, "x": -88.23598025952114, "y": 40.09277821103967, "z": 202.25459024857673, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.183278816221561, "steering_wheel_angle": -3.545, "front_wheel_angle": -0.1711570913272038, "heading_rate": -0.39228449489800793, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059848.729414}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.545, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059848.729414}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059848.8295612, "x": -88.23598025952114, "y": 40.09277821103967, "z": 202.25459024857673, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": -4.154, "front_wheel_angle": -0.20246088651307656, "heading_rate": -0.4586575901381077, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059848.8293831}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.154, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059848.8293831}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059848.9295235, "x": -88.23598025952114, "y": 40.09277821103967, "z": 202.25459024857673, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1966388162215615, "steering_wheel_angle": -4.768, "front_wheel_angle": -0.23467493124550637, "heading_rate": -0.5500708446224879, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059848.9294312}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.768, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059848.9294312}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059849.029487, "x": -88.23598025952114, "y": 40.09277821103967, "z": 202.25459024857673, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.210126816221561, "steering_wheel_angle": -5.222, "front_wheel_angle": -0.25894104297492315, "heading_rate": -0.6177270095935563, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059849.0293987}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.222, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059849.0293987}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059849.129638, "x": -88.2359485467996, "y": 40.09278863437604, "z": 202.26316636052064, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.210126816221561, "steering_wheel_angle": -5.373, "front_wheel_angle": -0.26709975071314035, "heading_rate": -0.6381329205718044, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059849.1294057}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.373, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059849.1294057}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059849.2294981, "x": -88.2359485467996, "y": 40.09278863437604, "z": 202.26316636052064, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.223742816221561, "steering_wheel_angle": -5.368, "front_wheel_angle": -0.2668288778268903, "heading_rate": -0.6459960846657984, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059849.2293987}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.368, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059849.2293987}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059849.3295174, "x": -88.2359485467996, "y": 40.09278863437604, "z": 202.26316636052064, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.237486816221562, "steering_wheel_angle": -5.46, "front_wheel_angle": -0.2718208688045035, "heading_rate": -0.6674024684603312, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059849.3294034}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.46, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059849.3294034}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059849.429557, "x": -88.2359485467996, "y": 40.09278863437604, "z": 202.26316636052064, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.237486816221562, "steering_wheel_angle": -5.653, "front_wheel_angle": -0.2823482572814258, "heading_rate": -0.6946498690964158, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059849.4294457}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.653, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059849.4294457}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059849.530127, "x": -88.2359485467996, "y": 40.09278863437604, "z": 202.26316636052064, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.2531018162215615, "steering_wheel_angle": -5.751, "front_wheel_angle": -0.2877227239245648, "heading_rate": -0.7190281090345599, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059849.5295084}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.751, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059849.5295084}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059849.630043, "x": -88.2359117476746, "y": 40.0927918848744, "z": 202.25957577525963, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.2531018162215615, "steering_wheel_angle": -5.716, "front_wheel_angle": -0.2858010115164598, "heading_rate": -0.7139529165715617, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059849.6295195}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.716, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059849.6295195}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059849.729496, "x": -88.2359117476746, "y": 40.0927918848744, "z": 202.25957577525963, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.267117816221561, "steering_wheel_angle": -5.561, "front_wheel_angle": -0.27732065282411633, "heading_rate": -0.700519779517257, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059849.7294004}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.561, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059849.7294004}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059849.8295226, "x": -88.2359117476746, "y": 40.0927918848744, "z": 202.25957577525963, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.267117816221561, "steering_wheel_angle": -5.136, "front_wheel_angle": -0.25431421349747413, "heading_rate": -0.6397022850335164, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059849.8294294}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.136, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059849.8294294}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059849.9295669, "x": -88.2359117476746, "y": 40.0927918848744, "z": 202.25957577525963, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.267117816221561, "steering_wheel_angle": -4.431, "front_wheel_angle": -0.21691028868295123, "heading_rate": -0.5423350984395297, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059849.9294412}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.431, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059849.9294412}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059850.029748, "x": -88.2359117476746, "y": 40.0927918848744, "z": 202.25957577525963, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": -3.646, "front_wheel_angle": -0.17630569837889948, "heading_rate": -0.44399677311510843, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059850.0294251}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.646, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059850.0294251}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059850.1295383, "x": -88.23587451694736, "y": 40.092786736167064, "z": 202.24666936232205, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": -2.861, "front_wheel_angle": -0.13672088001572794, "heading_rate": -0.34287313189086116, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059850.129438}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.861, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059850.129438}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059850.2295349, "x": -88.23587451694736, "y": 40.092786736167064, "z": 202.24666936232205, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": -2.063, "front_wheel_angle": -0.0974503754650377, "heading_rate": -0.24363633327930395, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059850.2294075}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.063, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059850.2294075}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059850.3295135, "x": -88.23587451694736, "y": 40.092786736167064, "z": 202.24666936232205, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": -1.265, "front_wheel_angle": -0.05909006045470825, "heading_rate": -0.14928386315251127, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059850.3294027}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.265, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059850.3294027}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059850.4296048, "x": -88.23587451694736, "y": 40.092786736167064, "z": 202.24666936232205, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": -0.486, "front_wheel_angle": -0.022463097299950587, "heading_rate": -0.056693758128763365, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059850.429474}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.486, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059850.429474}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059850.5295167, "x": -88.23587451694736, "y": 40.092786736167064, "z": 202.24666936232205, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": 0.217, "front_wheel_angle": 0.009994045779712853, "heading_rate": 0.025220189575008798, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059850.5294251}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.217, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059850.5294251}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059850.6295187, "x": -88.23583832249045, "y": 40.092778179114916, "z": 202.2564795942576, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3099338162215615, "steering_wheel_angle": 0.909, "front_wheel_angle": 0.04225437774408319, "heading_rate": 0.10801102042234233, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059850.6294296}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.54, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.909, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059850.6294296}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059850.7294955, "x": -88.23583832249045, "y": 40.092778179114916, "z": 202.2564795942576, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3099338162215615, "steering_wheel_angle": 1.6, "front_wheel_angle": 0.07508689326143134, "heading_rate": 0.1921848655441332, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059850.7293994}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.54, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.6, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059850.7293994}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059850.829513, "x": -88.23583832249045, "y": 40.092778179114916, "z": 202.2564795942576, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.324461816221562, "steering_wheel_angle": 2.265, "front_wheel_angle": 0.1073024440258679, "heading_rate": 0.2785472825829258, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059850.8294}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.265, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059850.8294}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059850.9295158, "x": -88.23583832249045, "y": 40.092778179114916, "z": 202.2564795942576, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.340958816221562, "steering_wheel_angle": 2.888, "front_wheel_angle": 0.13806628312893698, "heading_rate": 0.3642017924751479, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059850.9294012}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.888, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059850.9294012}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059851.0294993, "x": -88.23583832249045, "y": 40.092778179114916, "z": 202.2564795942576, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.355758816221561, "steering_wheel_angle": 3.471, "front_wheel_angle": 0.16739545631265432, "heading_rate": 0.44818436047158666, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059851.0293987}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.471, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059851.0293987}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059851.1295414, "x": -88.2358020038412, "y": 40.09277227887215, "z": 202.24682470911898, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.340958816221562, "steering_wheel_angle": 3.926, "front_wheel_angle": 0.1906677821869484, "heading_rate": 0.5059036162730474, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059851.1294389}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.926, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059851.1294389}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059851.230217, "x": -88.2358020038412, "y": 40.09277227887215, "z": 202.24682470911898, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.355758816221561, "steering_wheel_angle": 4.085, "front_wheel_angle": 0.19888247736777992, "heading_rate": 0.534571542167143, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059851.2295341}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.085, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059851.2295341}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059851.3295083, "x": -88.2358020038412, "y": 40.09277227887215, "z": 202.24682470911898, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": 4.083, "front_wheel_angle": 0.19877887823013457, "heading_rate": 0.5405805760321674, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059851.32941}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.083, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059851.32941}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059851.4294934, "x": -88.2358020038412, "y": 40.09277227887215, "z": 202.24682470911898, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": 4.013, "front_wheel_angle": 0.19515724886475974, "heading_rate": 0.5304745487998972, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059851.4293976}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059851.4293976}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059851.529496, "x": -88.2358020038412, "y": 40.09277227887215, "z": 202.24682470911898, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.355758816221561, "steering_wheel_angle": 3.866, "front_wheel_angle": 0.18757910004151246, "heading_rate": 0.5034428507746268, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059851.5293968}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.866, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059851.5293968}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059851.629543, "x": -88.23576502148607, "y": 40.09277305228132, "z": 202.29544955873112, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": 3.804, "front_wheel_angle": 0.18439385117913512, "heading_rate": 0.5005238732183287, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059851.6294308}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.804, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059851.6294308}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059851.7296796, "x": -88.23576502148607, "y": 40.09277305228132, "z": 202.29544955873112, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": 3.845, "front_wheel_angle": 0.18649950006882007, "heading_rate": 0.512270090198331, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059851.7294817}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.845, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059851.7294817}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059851.8295243, "x": -88.23576502148607, "y": 40.09277305228132, "z": 202.29544955873112, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": 3.832, "front_wheel_angle": 0.1858315489853181, "heading_rate": 0.5045173584716965, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059851.8294272}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.832, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059851.8294272}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059851.929522, "x": -88.23576502148607, "y": 40.09277305228132, "z": 202.29544955873112, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": 3.758, "front_wheel_angle": 0.18203477546267224, "heading_rate": 0.4997279767769843, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059851.9294052}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.758, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059851.9294052}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059852.0295525, "x": -88.23576502148607, "y": 40.09277305228132, "z": 202.29544955873112, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": 3.597, "front_wheel_angle": 0.17380576289950486, "heading_rate": 0.47666495196336844, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059852.0294383}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.597, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059852.0294383}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059852.1296635, "x": -88.23572867984203, "y": 40.09278155302152, "z": 200.6680697753449, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": 3.348, "front_wheel_angle": 0.16116267583136404, "heading_rate": 0.44135931816005697, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059852.1294224}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.348, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059852.1294224}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059852.2294917, "x": -88.23572867984203, "y": 40.09278155302152, "z": 202.33512112976805, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": 3.015, "front_wheel_angle": 0.1444097556437475, "heading_rate": 0.39479814246806305, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059852.2293959}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059852.2293959}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059852.3294919, "x": -88.23572867984203, "y": 40.09278155302152, "z": 202.33512112976805, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": 2.532, "front_wheel_angle": 0.12041595992587088, "heading_rate": 0.32849980257099043, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059852.329396}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.532, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059852.329396}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059852.4297192, "x": -88.23572867984203, "y": 40.09278155302152, "z": 202.33512112976805, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": 1.856, "front_wheel_angle": 0.0874149008806063, "heading_rate": 0.23792412795270076, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059852.4294584}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.856, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059852.4294584}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059852.5295668, "x": -88.23572867984203, "y": 40.09278155302152, "z": 202.33512112976805, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": 1.091, "front_wheel_angle": 0.050840579426136824, "heading_rate": 0.13814327242575195, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059852.5294392}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.091, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059852.5294392}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059852.6295714, "x": -88.23569413999591, "y": 40.092795701512976, "z": 202.36034712266596, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": 0.371, "front_wheel_angle": 0.017121501183618642, "heading_rate": 0.046486743032275735, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059852.6294339}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.371, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059852.6294339}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059852.7295413, "x": -88.23569413999591, "y": 40.092795701512976, "z": 202.36034712266596, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.400926816221562, "steering_wheel_angle": -0.317, "front_wheel_angle": -0.014618936576890385, "heading_rate": -0.040147830448060993, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059852.729405}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059852.729405}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059852.8295588, "x": -88.23569413999591, "y": 40.092795701512976, "z": 202.36034712266596, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.400926816221562, "steering_wheel_angle": -0.993, "front_wheel_angle": -0.046211872687489615, "heading_rate": -0.1269925467371703, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059852.8294408}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.993, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059852.8294408}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059852.9296699, "x": -88.23569413999591, "y": 40.092795701512976, "z": 202.36034712266596, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.400926816221562, "steering_wheel_angle": -1.662, "front_wheel_angle": -0.07806425580663867, "heading_rate": -0.21480829159728881, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059852.9294295}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.662, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059852.9294295}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059853.0295072, "x": -88.23569413999591, "y": 40.092795701512976, "z": 202.36034712266596, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": -2.284, "front_wheel_angle": -0.10823216021216073, "heading_rate": -0.3022016349979897, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059853.0293992}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.284, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059853.0293992}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059853.129551, "x": -88.23565816582982, "y": 40.09281056288259, "z": 202.42387938554737, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.400926816221562, "steering_wheel_angle": -2.755, "front_wheel_angle": -0.13144972097029634, "heading_rate": -0.36306681740610525, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059853.1294127}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.755, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059853.1294127}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059853.2295566, "x": -88.23565816582982, "y": 40.09281056288259, "z": 202.42387938554737, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.400926816221562, "steering_wheel_angle": -3.102, "front_wheel_angle": -0.1487697613483811, "heading_rate": -0.41157659987998285, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059853.2294307}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.102, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059853.2294307}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059853.3295515, "x": -88.23565816582982, "y": 40.09281056288259, "z": 202.42387938554737, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": -3.356, "front_wheel_angle": -0.16156731771337357, "heading_rate": -0.45331038832877163, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059853.3294044}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.356, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059853.3294044}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059853.4295812, "x": -88.23565816582982, "y": 40.09281056288259, "z": 202.42387938554737, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": -3.512, "front_wheel_angle": -0.16947850151591934, "heading_rate": -0.47592751441960157, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059853.429452}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.512, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059853.429452}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059853.5295377, "x": -88.23565816582982, "y": 40.09281056288259, "z": 202.42387938554737, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": -3.592, "front_wheel_angle": -0.17355088992695727, "heading_rate": -0.48759369719830875, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059853.529435}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.592, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059853.529435}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059853.6297038, "x": -88.23561780945238, "y": 40.09282029701534, "z": 202.46403811429454, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": -3.679, "front_wheel_angle": -0.17799156447053688, "heading_rate": -0.5003339244954932, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059853.629439}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.679, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059853.629439}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059853.729503, "x": -88.23561780945238, "y": 40.09282029701534, "z": 202.46403811429454, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": -3.751, "front_wheel_angle": -0.1816760961732718, "heading_rate": -0.5109202295047146, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059853.7293925}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.751, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059853.7293925}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059853.8294833, "x": -88.23561780945238, "y": 40.09282029701534, "z": 202.46403811429454, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": -3.875, "front_wheel_angle": -0.18804201373868257, "heading_rate": -0.5351911680979176, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059853.8293934}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.875, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059853.8293934}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059853.9294853, "x": -88.23561780945238, "y": 40.09282029701534, "z": 202.46403811429454, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": -3.961, "front_wheel_angle": -0.19247233662830876, "heading_rate": -0.5420234699665418, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059853.929396}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.961, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059853.929396}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059854.029529, "x": -88.23561780945238, "y": 40.09282029701534, "z": 202.46403811429454, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": -3.981, "front_wheel_angle": -0.19350444813235387, "heading_rate": -0.5511272913250584, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059854.0294042}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.981, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059854.0294042}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059854.1295457, "x": -88.23557497048753, "y": 40.0928224949869, "z": 202.45681456286582, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": -3.985, "front_wheel_angle": -0.19371095241435174, "heading_rate": -0.551730410855509, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059854.1294208}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.985, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059854.1294208}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059854.2295058, "x": -88.23557497048753, "y": 40.0928224949869, "z": 202.45681456286582, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": -3.982, "front_wheel_angle": -0.19355607163916053, "heading_rate": -0.5451527473738863, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059854.2293983}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.982, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059854.2293983}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059854.3295238, "x": -88.23557497048753, "y": 40.0928224949869, "z": 202.45681456286582, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": -3.934, "front_wheel_angle": -0.19108006796095342, "heading_rate": -0.5440502447879263, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059854.3294003}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.934, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059854.3294003}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059854.4296625, "x": -88.23557497048753, "y": 40.0928224949869, "z": 202.45681456286582, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": -3.84, "front_wheel_angle": -0.1862425621053696, "heading_rate": -0.5240604213921091, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059854.4293835}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.84, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059854.4293835}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059854.5294917, "x": -88.23557497048753, "y": 40.0928224949869, "z": 202.45681456286582, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": -3.654, "front_wheel_angle": -0.17671422761594818, "heading_rate": -0.5022477320883678, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059854.529396}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.654, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059854.529396}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059854.6295006, "x": -88.23553315988401, "y": 40.09281638682903, "z": 202.41915225492255, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": -3.348, "front_wheel_angle": -0.16116267583136404, "heading_rate": -0.45215515759706554, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059854.629411}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.348, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059854.629411}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059854.7295103, "x": -88.23553315988401, "y": 40.09281638682903, "z": 202.41915225492255, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": -2.876, "front_wheel_angle": -0.13746818786160925, "heading_rate": -0.38908327238208473, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059854.7293978}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059854.7293978}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059854.8294342, "x": -88.23553315988401, "y": 40.09281638682903, "z": 202.41915225492255, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": -2.221, "front_wheel_angle": -0.10515143100231303, "heading_rate": -0.29353507092569153, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059854.829334}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.221, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059854.829334}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059854.9295475, "x": -88.23553315988401, "y": 40.09281638682903, "z": 202.41915225492255, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": -1.446, "front_wheel_angle": -0.06771426791564791, "heading_rate": -0.18861868198437806, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059854.9294052}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.446, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059854.9294052}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059855.029514, "x": -88.23553315988401, "y": 40.09281638682903, "z": 202.41915225492255, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": -0.686, "front_wheel_angle": -0.031792313979288396, "heading_rate": -0.08944602098945974, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059855.0293999}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.686, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059855.0293999}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059855.1295946, "x": -88.23549470972495, "y": 40.09280346127369, "z": 202.3929936507221, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": 0.022, "front_wheel_angle": 0.0010106242725761874, "heading_rate": 0.002842381734320275, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059855.1294065}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.022, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059855.1294065}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059855.2295306, "x": -88.23549470972495, "y": 40.09280346127369, "z": 202.3929936507221, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": 0.711, "front_wheel_angle": 0.03296202393511355, "heading_rate": 0.09273928167318438, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059855.2294254}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.711, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059855.2294254}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059855.329517, "x": -88.23549470972495, "y": 40.09280346127369, "z": 202.3929936507221, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": 1.389, "front_wheel_angle": 0.06499360414333141, "heading_rate": 0.18305233223714057, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059855.329422}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.389, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059855.329422}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059855.4295387, "x": -88.23549470972495, "y": 40.09280346127369, "z": 202.3929936507221, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.464913816221562, "steering_wheel_angle": 2.04, "front_wheel_angle": 0.0963323206566969, "heading_rate": 0.27781532163197936, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059855.429402}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.04, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059855.429402}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059855.5295167, "x": -88.23549470972495, "y": 40.09280346127369, "z": 202.3929936507221, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.449201816221562, "steering_wheel_angle": 2.579, "front_wheel_angle": 0.12273525005815494, "heading_rate": 0.3507915734305069, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059855.5294218}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.579, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059855.5294218}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059855.6300328, "x": -88.23545721686205, "y": 40.092791049939066, "z": 202.3825702172106, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.464913816221562, "steering_wheel_angle": 2.887, "front_wheel_angle": 0.13801643339649206, "heading_rate": 0.3993360609140135, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059855.6294997}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.887, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059855.6294997}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059855.7295694, "x": -88.23545721686205, "y": 40.092791049939066, "z": 202.3825702172106, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.449201816221562, "steering_wheel_angle": 3.067, "front_wheel_angle": 0.14701431294430806, "heading_rate": 0.42111018019932633, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059855.7294095}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.067, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059855.7294095}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059855.8295157, "x": -88.23545721686205, "y": 40.092791049939066, "z": 202.3825702172106, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.449201816221562, "steering_wheel_angle": 3.166, "front_wheel_angle": 0.15198470191944558, "heading_rate": 0.4355654315102701, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059855.829422}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059855.829422}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059855.9295259, "x": -88.23545721686205, "y": 40.092791049939066, "z": 202.3825702172106, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.449201816221562, "steering_wheel_angle": 3.211, "front_wheel_angle": 0.15424907797879994, "heading_rate": 0.4421581137377509, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059855.9293988}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.211, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059855.9293988}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059856.0296266, "x": -88.23545721686205, "y": 40.092791049939066, "z": 202.3825702172106, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": 3.261, "front_wheel_angle": 0.15676881881172522, "heading_rate": 0.4445601895360229, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059856.029421}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.261, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059856.029421}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059856.129501, "x": -88.23541766531307, "y": 40.09278495452726, "z": 202.3834075259548, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": 3.341, "front_wheel_angle": 0.16080869854371158, "heading_rate": 0.45621373771982354, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059856.129406}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.341, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059856.129406}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059856.2295156, "x": -88.23541766531307, "y": 40.09278495452726, "z": 202.3834075259548, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": 3.419, "front_wheel_angle": 0.164757475163112, "heading_rate": 0.4676192546590527, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059856.229419}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.419, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059856.229419}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059856.3296418, "x": -88.23541766531307, "y": 40.09278495452726, "z": 202.3834075259548, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": 3.495, "front_wheel_angle": 0.1686144674889243, "heading_rate": 0.4734544172705046, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059856.329435}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.495, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059856.329435}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059856.429696, "x": -88.23541766531307, "y": 40.09278495452726, "z": 202.3834075259548, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": 3.587, "front_wheel_angle": 0.1732960580767805, "heading_rate": 0.4923335681042364, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059856.429396}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.587, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059856.429396}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059856.5296252, "x": -88.23541766531307, "y": 40.09278495452726, "z": 202.3834075259548, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.400926816221562, "steering_wheel_angle": 3.765, "front_wheel_angle": 0.1823935366648274, "heading_rate": 0.5064988813991869, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059856.5294113}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.765, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059856.5294113}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059856.6295958, "x": -88.23537778551656, "y": 40.09278575625859, "z": 202.42001062436717, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.400926816221562, "steering_wheel_angle": 3.871, "front_wheel_angle": 0.187836257414803, "heading_rate": 0.5219692469227347, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059856.629412}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.871, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059856.629412}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059856.7298481, "x": -88.23537778551656, "y": 40.09278575625859, "z": 202.42001062436717, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": 3.87, "front_wheel_angle": 0.18778482256011741, "heading_rate": 0.5285034211174878, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059856.729444}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.87, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059856.729444}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059856.8294926, "x": -88.23537778551656, "y": 40.09278575625859, "z": 202.42001062436717, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": 3.876, "front_wheel_angle": 0.1880934570467702, "heading_rate": 0.5108046261803163, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059856.8293934}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059856.8293934}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059856.9294806, "x": -88.23537778551656, "y": 40.09278575625859, "z": 202.42001062436717, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.355758816221561, "steering_wheel_angle": 3.878, "front_wheel_angle": 0.18819634873665433, "heading_rate": 0.5051391889778816, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059856.9293897}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.878, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059856.9293897}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059857.0294855, "x": -88.23537778551656, "y": 40.09278575625859, "z": 202.42001062436717, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.355758816221561, "steering_wheel_angle": 3.878, "front_wheel_angle": 0.18819634873665433, "heading_rate": 0.5051391889778816, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059857.029396}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.878, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059857.029396}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059857.1295435, "x": -88.23534069323111, "y": 40.092793819035876, "z": 202.45381799454765, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": 3.87, "front_wheel_angle": 0.18778482256011741, "heading_rate": 0.5099464189715086, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059857.1294181}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.87, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059857.1294181}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059857.2295234, "x": -88.23534069323111, "y": 40.092793819035876, "z": 202.45381799454765, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": 3.84, "front_wheel_angle": 0.1862425621053696, "heading_rate": 0.5115477427914547, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059857.2294004}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.84, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059857.2294004}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059857.329569, "x": -88.23534069323111, "y": 40.092793819035876, "z": 202.45381799454765, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": 3.717, "front_wheel_angle": 0.1799351029705097, "heading_rate": 0.4881523688308039, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059857.3294244}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.717, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059857.3294244}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059857.4295092, "x": -88.23534069323111, "y": 40.092793819035876, "z": 202.45381799454765, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.340958816221562, "steering_wheel_angle": 3.367, "front_wheel_angle": 0.1621238683547414, "heading_rate": 0.42870450049616626, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059857.429392}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059857.429392}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059857.529494, "x": -88.23534069323111, "y": 40.092793819035876, "z": 202.45381799454765, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.324461816221562, "steering_wheel_angle": 2.729, "front_wheel_angle": 0.13015941002222814, "heading_rate": 0.33849781221339353, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059857.5293941}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.729, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059857.5293941}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059857.6295514, "x": -88.23530839575557, "y": 40.09280825702865, "z": 202.5052890736402, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": 1.953, "front_wheel_angle": 0.0921099647712663, "heading_rate": 0.2330933193778574, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059857.629442}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.953, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059857.629442}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059857.7295141, "x": -88.23530839575557, "y": 40.09280825702865, "z": 202.5052890736402, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": 1.153, "front_wheel_angle": 0.05377545674445793, "heading_rate": 0.13414785561971884, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059857.7294195}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.153, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059857.7294195}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059857.829479, "x": -88.23530839575557, "y": 40.09280825702865, "z": 202.5052890736402, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.2531018162215615, "steering_wheel_angle": 0.367, "front_wheel_angle": 0.0169360023123595, "heading_rate": 0.041153127819057146, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059857.8293889}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059857.8293889}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059857.9296892, "x": -88.23530839575557, "y": 40.09280825702865, "z": 202.5052890736402, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": -0.365, "front_wheel_angle": -0.016843260309156186, "heading_rate": -0.04250693443658797, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059857.9294064}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.365, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059857.9294064}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059858.0295863, "x": -88.23530839575557, "y": 40.09280825702865, "z": 202.5052890736402, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.2531018162215615, "steering_wheel_angle": -1.062, "front_wheel_angle": -0.0494695498767464, "heading_rate": -0.12029369201207633, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059858.0294266}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.062, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059858.0294266}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059858.1295378, "x": -88.23527879612895, "y": 40.092824876350896, "z": 202.49852246452147, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.2531018162215615, "steering_wheel_angle": -1.764, "front_wheel_angle": -0.08297404723573182, "heading_rate": -0.20206493668895384, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059858.129421}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059858.129421}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059858.229524, "x": -88.23527879612895, "y": 40.092824876350896, "z": 202.49852246452147, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.210126816221561, "steering_wheel_angle": -2.431, "front_wheel_angle": -0.11544306760768239, "heading_rate": -0.270419211396218, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059858.2294207}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.431, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059858.2294207}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059858.329526, "x": -88.23527879612895, "y": 40.092824876350896, "z": 202.49852246452147, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.223742816221561, "steering_wheel_angle": -3.071, "front_wheel_angle": -0.14721483848970676, "heading_rate": -0.35044537460394004, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059858.3294232}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.071, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059858.3294232}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059858.4295402, "x": -88.23527879612895, "y": 40.092824876350896, "z": 202.49852246452147, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": -3.708, "front_wheel_angle": -0.17947457426925031, "heading_rate": -0.40537540968050256, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059858.429424}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.708, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059858.429424}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059858.5295103, "x": -88.23527879612895, "y": 40.092824876350896, "z": 202.49852246452147, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": -4.339, "front_wheel_angle": -0.21209618120578524, "heading_rate": -0.4811387769019324, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059858.5294194}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.339, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059858.5294194}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059858.6295028, "x": -88.23524847346931, "y": 40.092838456172814, "z": 202.47017431841368, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": -4.977, "front_wheel_angle": -0.2457973642733206, "heading_rate": -0.5370186970134769, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059858.6294165}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.977, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059858.6294165}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059858.7295265, "x": -88.23524847346931, "y": 40.092838456172814, "z": 202.47017431841368, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": -5.593, "front_wheel_angle": -0.2790674396857173, "heading_rate": -0.6133852295342386, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059858.7294319}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.593, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059858.7294319}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059858.8295557, "x": -88.23524847346931, "y": 40.092838456172814, "z": 202.47017431841368, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": -6.181, "front_wheel_angle": -0.3115414100637526, "heading_rate": -0.6792776431568261, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059858.829419}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.181, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059858.829419}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059858.9295342, "x": -88.23524847346931, "y": 40.092838456172814, "z": 202.47017431841368, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": -6.742, "front_wheel_angle": -0.3432213651599507, "heading_rate": -0.7300865065565914, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059858.929418}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.742, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059858.929418}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059859.0295203, "x": -88.23524847346931, "y": 40.092838456172814, "z": 202.47017431841368, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": -7.198, "front_wheel_angle": -0.36950629088704, "heading_rate": -0.7791291940865007, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059859.0294204}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.198, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059859.0294204}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059859.1294956, "x": -88.23521712548282, "y": 40.0928449103549, "z": 202.39782594559566, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": -7.651, "front_wheel_angle": -0.3961223722748085, "heading_rate": -0.8282912621503307, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059859.12939}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.651, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059859.12939}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059859.229488, "x": -88.23521712548282, "y": 40.0928449103549, "z": 202.39782594559566, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": -7.962, "front_wheel_angle": -0.4147016451296921, "heading_rate": -0.8443521739947187, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059859.2293916}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.962, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059859.2293916}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059859.3294837, "x": -88.23521712548282, "y": 40.0928449103549, "z": 202.39782594559566, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": -8.205, "front_wheel_angle": -0.4294000551645408, "heading_rate": -0.8621305990628412, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059859.3293889}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.205, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059859.3293889}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059859.4294753, "x": -88.23521712548282, "y": 40.0928449103549, "z": 202.39782594559566, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": -8.495, "front_wheel_angle": -0.4471578906881376, "heading_rate": -0.8879252560457244, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059859.4293869}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.495, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059859.4293869}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059859.5294807, "x": -88.23521712548282, "y": 40.0928449103549, "z": 202.39782594559566, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": -8.871, "front_wheel_angle": -0.47054787637869566, "heading_rate": -0.9755850344649949, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059859.529388}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.871, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059859.529388}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059859.6295035, "x": -88.2351880069634, "y": 40.092842008922354, "z": 202.34023280237932, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": -9.184, "front_wheel_angle": -0.490349229962978, "heading_rate": -0.9884322317302947, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059859.6293914}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.184, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059859.6293914}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059859.7295256, "x": -88.2351880069634, "y": 40.092842008922354, "z": 202.34023280237932, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": -9.425, "front_wheel_angle": -0.5058098476901471, "heading_rate": -1.0082171593989142, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059859.7294014}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.425, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059859.7294014}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059859.8295155, "x": -88.2351880069634, "y": 40.092842008922354, "z": 202.34023280237932, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": -9.614, "front_wheel_angle": -0.5180699779279497, "heading_rate": -1.0197690607263907, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059859.8294194}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.614, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059859.8294194}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059859.929526, "x": -88.2351880069634, "y": 40.092842008922354, "z": 202.34023280237932, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": -9.826, "front_wheel_angle": -0.5319685595616759, "heading_rate": -1.0345859176926873, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059859.929432}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.826, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059859.929432}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059860.0296667, "x": -88.2351880069634, "y": 40.092842008922354, "z": 202.34023280237932, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": -10.002, "front_wheel_angle": -0.5436283464477916, "heading_rate": -1.1001467511430205, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059860.0294225}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.002, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059860.0294225}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059860.1295195, "x": -88.23516424416975, "y": 40.09283058530783, "z": 202.33963050932502, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": -10.18, "front_wheel_angle": -0.5555361022187122, "heading_rate": -1.1105575873666405, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059860.1294284}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059860.1294284}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059860.2295012, "x": -88.23516424416975, "y": 40.09283058530783, "z": 202.33963050932502, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": -10.533, "front_wheel_angle": -0.5795082939467602, "heading_rate": -1.1504283508630266, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059860.2294161}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.533, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059860.2294161}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059860.3294864, "x": -88.23516424416975, "y": 40.09283058530783, "z": 202.33963050932502, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9483428162215617, "steering_wheel_angle": -10.844, "front_wheel_angle": -0.6010415636123453, "heading_rate": -1.1383142883782202, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059860.3293893}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.25, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.844, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059860.3293893}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059860.4295325, "x": -88.23516424416975, "y": 40.09283058530783, "z": 202.33963050932502, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": -11.131, "front_wheel_angle": -0.6212765571445066, "heading_rate": -1.3030487513209286, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059860.429418}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.131, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059860.429418}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059860.529572, "x": -88.23516424416975, "y": 40.09283058530783, "z": 202.33963050932502, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": -11.28, "front_wheel_angle": -0.6319258554915622, "heading_rate": -1.30971636656985, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059860.5294018}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.28, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059860.5294018}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059860.6295152, "x": -88.23514886762193, "y": 40.092813740926374, "z": 202.33013760023965, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": -11.289, "front_wheel_angle": -0.6325723433305981, "heading_rate": -1.2628137730306352, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059860.629417}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059860.629417}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059860.7295113, "x": -88.23514886762193, "y": 40.092813740926374, "z": 202.33013760023965, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9483428162215617, "steering_wheel_angle": -11.281, "front_wheel_angle": -0.6319976690618014, "heading_rate": -1.2155312819632493, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059860.7294152}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.25, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.281, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059860.7294152}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059860.829605, "x": -88.23514886762193, "y": 40.092813740926374, "z": 202.33013760023965, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9376068162215616, "steering_wheel_angle": -11.277, "front_wheel_angle": -0.6317104423774298, "heading_rate": -1.1919321628801853, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059860.8294356}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.17, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059860.8294356}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059860.9294832, "x": -88.23514886762193, "y": 40.092813740926374, "z": 202.33013760023965, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": -11.28, "front_wheel_angle": -0.6319258554915622, "heading_rate": -1.26110244029979, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059860.9293895}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.28, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059860.9293895}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059861.0294793, "x": -88.23514886762193, "y": 40.092813740926374, "z": 202.33013760023965, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": -11.28, "front_wheel_angle": -0.6319258554915622, "heading_rate": -1.26110244029979, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059861.029386}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.28, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059861.029386}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059861.129487, "x": -88.23514502059724, "y": 40.09279458151872, "z": 202.28078452759738, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9592068162215615, "steering_wheel_angle": -11.295, "front_wheel_angle": -0.6330035425429016, "heading_rate": -1.2410272031976761, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059861.129389}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.295, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059861.129389}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059861.2295742, "x": -88.23514502059724, "y": 40.09279458151872, "z": 202.28078452759738, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9376068162215616, "steering_wheel_angle": -11.329, "front_wheel_angle": -0.6354501474515283, "heading_rate": -1.2013112036238411, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059861.2294025}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.17, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.329, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059861.2294025}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059861.329812, "x": -88.23514502059724, "y": 40.09279458151872, "z": 202.28078452759738, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9269988162215617, "steering_wheel_angle": -11.367, "front_wheel_angle": -0.6381909424646288, "heading_rate": -1.1850386786056923, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059861.3294668}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.09, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059861.3294668}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059861.4294865, "x": -88.23514502059724, "y": 40.09279458151872, "z": 202.28078452759738, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9178218162215614, "steering_wheel_angle": -11.366, "front_wheel_angle": -0.6381187299548031, "heading_rate": -1.1645810688373954, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059861.4293876}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.366, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059861.4293876}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059861.529686, "x": -88.23514502059724, "y": 40.09279458151872, "z": 202.28078452759738, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9152178162215616, "steering_wheel_angle": -11.357, "front_wheel_angle": -0.6374690277270771, "heading_rate": -1.157214387273663, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059861.5294557}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.357, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059861.5294557}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059861.6295555, "x": -88.23515223638016, "y": 40.092776181732624, "z": 202.30572915504143, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9376068162215616, "steering_wheel_angle": -11.333, "front_wheel_angle": -0.635738335562069, "heading_rate": -1.2020361127672154, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059861.6293993}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.17, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.333, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059861.6293993}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059861.7294836, "x": -88.23515223638016, "y": 40.092776181732624, "z": 202.30572915504143, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9456468162215614, "steering_wheel_angle": -11.236, "front_wheel_angle": -0.6287705999211803, "heading_rate": -1.2016396546016888, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059861.7293868}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.236, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059861.7293868}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059861.8294919, "x": -88.23515223638016, "y": 40.092776181732624, "z": 202.30572915504143, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9456468162215614, "steering_wheel_angle": -11.117, "front_wheel_angle": -0.6202810975864068, "heading_rate": -1.1803244203411225, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059861.8293884}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.117, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059861.8293884}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059861.9294972, "x": -88.23515223638016, "y": 40.092776181732624, "z": 202.30572915504143, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8997618162215613, "steering_wheel_angle": -11.101, "front_wheel_angle": -0.6191444996911868, "heading_rate": -1.0800620728484471, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059861.9294019}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.88, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.101, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059861.9294019}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059862.0295186, "x": -88.23515223638016, "y": 40.092776181732624, "z": 202.30572915504143, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9336138162215617, "steering_wheel_angle": -11.101, "front_wheel_angle": -0.6191444996911868, "heading_rate": -1.1524373663898377, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059862.0293906}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.14, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.101, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059862.0293906}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059862.1295276, "x": -88.23515223638016, "y": 40.092776181732624, "z": 202.30572915504143, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9100338162215618, "steering_wheel_angle": -11.1, "front_wheel_angle": -0.6190735001510069, "heading_rate": -1.102165801817311, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059862.1293936}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.96, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.1, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059862.1293936}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059862.229807, "x": -88.23516825122124, "y": 40.092762046262806, "z": 202.31781862148154, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9269988162215617, "steering_wheel_angle": -11.1, "front_wheel_angle": -0.6190735001510069, "heading_rate": -1.138348012483031, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059862.2294247}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.09, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.1, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059862.2294247}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059862.3296118, "x": -88.23516825122124, "y": 40.092762046262806, "z": 202.31781862148154, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9061668162215617, "steering_wheel_angle": -11.094, "front_wheel_angle": -0.6186475962334468, "heading_rate": -1.0928305999551104, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059862.3294187}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.094, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059862.3294187}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059862.4296992, "x": -88.23516825122124, "y": 40.092762046262806, "z": 202.31781862148154, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9126218162215616, "steering_wheel_angle": -11.069, "front_wheel_angle": -0.6168747151763609, "heading_rate": -1.1025864869405047, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059862.429414}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.069, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059862.429414}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059862.5295734, "x": -88.23516825122124, "y": 40.092762046262806, "z": 202.31781862148154, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9048818162215615, "steering_wheel_angle": -11.025, "front_wheel_angle": -0.6137611455773521, "heading_rate": -1.0788147212077912, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059862.5294063}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059862.5294063}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059862.6295347, "x": -88.23518995302392, "y": 40.092754123021855, "z": 202.28526943447793, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.919126816221562, "steering_wheel_angle": -10.889, "front_wheel_angle": -0.6041907361563748, "heading_rate": -1.0866937746558658, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059862.6294215}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.889, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059862.6294215}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059862.729662, "x": -88.23518995302392, "y": 40.092754123021855, "z": 202.28526943447793, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9061668162215617, "steering_wheel_angle": -10.756, "front_wheel_angle": -0.5949079293460791, "heading_rate": -1.038820762441985, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059862.7294118}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.756, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059862.7294118}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059862.8296545, "x": -88.23518995302392, "y": 40.092754123021855, "z": 202.28526943447793, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9416178162215614, "steering_wheel_angle": -10.481, "front_wheel_angle": -0.5759463159424426, "heading_rate": -1.0654055559420672, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059862.829401}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.481, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059862.829401}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059862.9295013, "x": -88.23518995302392, "y": 40.092754123021855, "z": 202.28526943447793, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9269988162215617, "steering_wheel_angle": -10.14, "front_wheel_angle": -0.5528499099575838, "heading_rate": -0.9858070647759848, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059862.929411}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.09, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.14, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059862.929411}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059863.0296514, "x": -88.23518995302392, "y": 40.092754123021855, "z": 202.28526943447793, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9336138162215617, "steering_wheel_angle": -9.851, "front_wheel_angle": -0.5336179854951707, "heading_rate": -0.9554139881710699, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059863.029429}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.14, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.851, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059863.029429}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059863.1294768, "x": -88.23521418247188, "y": 40.092752707669035, "z": 202.28290136607563, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9336138162215617, "steering_wheel_angle": -9.506, "front_wheel_angle": -0.5110493691050984, "heading_rate": -0.9068172282884616, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059863.129385}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.14, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.506, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059863.129385}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059863.2296083, "x": -88.23521418247188, "y": 40.092752707669035, "z": 202.28290136607563, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9389418162215613, "steering_wheel_angle": -9.096, "front_wheel_angle": -0.4847508338050831, "heading_rate": -0.8599441196204684, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059863.229444}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.096, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059863.229444}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059863.329488, "x": -88.23521418247188, "y": 40.092752707669035, "z": 202.28290136607563, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9496938162215613, "steering_wheel_angle": -8.622, "front_wheel_angle": -0.455011090267801, "heading_rate": -0.814143415864476, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059863.3294013}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.26, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.622, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059863.3294013}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059863.4294744, "x": -88.23521418247188, "y": 40.092752707669035, "z": 202.28290136607563, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.964686816221562, "steering_wheel_angle": -8.017, "front_wheel_angle": -0.4180142763427369, "heading_rate": -0.7582512000576533, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059863.4293847}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.37, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.017, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059863.4293847}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059863.5297124, "x": -88.23521418247188, "y": 40.092752707669035, "z": 202.28290136607563, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9376068162215616, "steering_wheel_angle": -7.236, "front_wheel_angle": -0.37171927939503224, "heading_rate": -0.6350167341188636, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059863.5294142}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.17, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.236, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059863.5294142}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059863.6295114, "x": -88.23523888999713, "y": 40.092757743350006, "z": 202.33717944942262, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9883338162215614, "steering_wheel_angle": -6.452, "front_wheel_angle": -0.32675705448339337, "heading_rate": -0.6010276458808357, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059863.6294193}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.54, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.452, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059863.6294193}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059863.7295232, "x": -88.23523888999713, "y": 40.092757743350006, "z": 202.33717944942262, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9402788162215616, "steering_wheel_angle": -5.635, "front_wheel_angle": -0.2813632440053969, "heading_rate": -0.4730622486831542, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059863.7294183}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.19, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.635, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059863.7294183}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059863.8295135, "x": -88.23523888999713, "y": 40.092757743350006, "z": 202.33717944942262, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": -4.882, "front_wheel_angle": -0.24073157180738297, "heading_rate": -0.4315293010600154, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059863.8294117}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.882, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059863.8294117}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059863.929527, "x": -88.23523888999713, "y": 40.092757743350006, "z": 202.33717944942262, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9592068162215615, "steering_wheel_angle": -4.299, "front_wheel_angle": -0.21000777591501343, "heading_rate": -0.360524212325067, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059863.929395}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.299, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059863.929395}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059864.0294833, "x": -88.23523888999713, "y": 40.092757743350006, "z": 202.33717944942262, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9785268162215615, "steering_wheel_angle": -3.734, "front_wheel_angle": -0.1808053585790176, "heading_rate": -0.3191888666016491, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059864.0293865}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.47, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.734, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059864.0293865}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059864.12947, "x": -88.23526287003831, "y": 40.092766673444395, "z": 202.3845161924878, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.968817816221562, "steering_wheel_angle": -3.083, "front_wheel_angle": -0.1478165654304631, "heading_rate": -0.25592641762706175, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059864.1293828}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.083, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059864.1293828}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059864.229478, "x": -88.23526287003831, "y": 40.092766673444395, "z": 202.3845161924878, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.968817816221562, "steering_wheel_angle": -2.363, "front_wheel_angle": -0.11210347085039339, "heading_rate": -0.19348905821823456, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059864.2293828}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.363, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059864.2293828}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059864.329498, "x": -88.23526287003831, "y": 40.092766673444395, "z": 202.3845161924878, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9729668162215614, "steering_wheel_angle": -1.637, "front_wheel_angle": -0.07686307005458828, "heading_rate": -0.13327169754217322, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059864.3294091}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.637, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059864.3294091}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059864.4298053, "x": -88.23526287003831, "y": 40.092766673444395, "z": 202.3845161924878, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9715818162215615, "steering_wheel_angle": -0.939, "front_wheel_angle": -0.04366671696330783, "heading_rate": -0.07544127212761896, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059864.4294298}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.42, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.939, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059864.4294298}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059864.529506, "x": -88.23526287003831, "y": 40.092766673444395, "z": 202.3845161924878, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9799218162215615, "steering_wheel_angle": -0.296, "front_wheel_angle": -0.013646689422086073, "heading_rate": -0.023883189112802145, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059864.5294104}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.296, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059864.5294104}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059864.6294703, "x": -88.23528557945953, "y": 40.09277634851639, "z": 202.40547256372554, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9729668162215614, "steering_wheel_angle": 0.327, "front_wheel_angle": 0.015082102583903858, "heading_rate": 0.026101086305539336, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059864.629382}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059864.629382}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059864.7294822, "x": -88.23528557945953, "y": 40.09277634851639, "z": 202.40547256372554, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9813188162215614, "steering_wheel_angle": 0.988, "front_wheel_angle": 0.04597605070017692, "heading_rate": 0.080694547991513, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059864.729386}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.49, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.988, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059864.729386}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059864.8295703, "x": -88.23528557945953, "y": 40.09277634851639, "z": 202.40547256372554, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.975742816221562, "steering_wheel_angle": 1.583, "front_wheel_angle": 0.07427144212850702, "heading_rate": 0.12934257129844048, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059864.8294287}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.45, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.583, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059864.8294287}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059864.9294786, "x": -88.23528557945953, "y": 40.09277634851639, "z": 202.40547256372554, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9799218162215615, "steering_wheel_angle": 1.917, "front_wheel_angle": 0.09036591961492912, "heading_rate": 0.15857222806487548, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059864.929388}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.917, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059864.929388}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059865.0294762, "x": -88.23528557945953, "y": 40.09277634851639, "z": 202.40547256372554, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9925668162215615, "steering_wheel_angle": 2.13, "front_wheel_angle": 0.10071162971965465, "heading_rate": 0.18039631792516153, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059865.0293834}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.13, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059865.0293834}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059865.1294763, "x": -88.23530862276932, "y": 40.09278482837224, "z": 202.43329485404308, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.975742816221562, "steering_wheel_angle": 2.421, "front_wheel_angle": 0.11495152341809829, "heading_rate": 0.20070287697144706, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059865.1293826}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.45, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.421, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059865.1293826}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059865.2297184, "x": -88.23530862276932, "y": 40.09278482837224, "z": 202.43329485404308, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9996618162215616, "steering_wheel_angle": 2.715, "front_wheel_angle": 0.129465051964921, "heading_rate": 0.23495815703408499, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059865.2294648}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.715, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059865.2294648}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059865.3301284, "x": -88.23530862276932, "y": 40.09278482837224, "z": 202.43329485404308, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9855218162215618, "steering_wheel_angle": 3.01, "front_wheel_angle": 0.14415953965462072, "heading_rate": 0.2563096923885567, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059865.3297374}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.01, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059865.3297374}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059865.4296317, "x": -88.23530862276932, "y": 40.09278482837224, "z": 202.43329485404308, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.003942816221562, "steering_wheel_angle": 3.229, "front_wheel_angle": 0.15515572692053883, "heading_rate": 0.28410931558124586, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059865.4293976}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059865.4293976}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059865.5295475, "x": -88.23530862276932, "y": 40.09278482837224, "z": 202.43329485404308, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0096788162215615, "steering_wheel_angle": 3.363, "front_wheel_angle": 0.16192146377823816, "heading_rate": 0.2992651988947984, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059865.5293903}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.363, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059865.5293903}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059865.629603, "x": -88.23533320690095, "y": 40.09279088461123, "z": 202.4398235949457, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.012558816221562, "steering_wheel_angle": 3.424, "front_wheel_angle": 0.16501093676761724, "heading_rate": 0.3063801702293516, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059865.6295118}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.71, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.424, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059865.6295118}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059865.7294867, "x": -88.23533320690095, "y": 40.09279088461123, "z": 202.4398235949457, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.025617816221562, "steering_wheel_angle": 3.423, "front_wheel_angle": 0.1649602412103384, "heading_rate": 0.3121368791312075, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059865.7293842}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.8, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.423, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059865.7293842}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059865.8294704, "x": -88.23533320690095, "y": 40.09279088461123, "z": 202.4398235949457, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.021246816221561, "steering_wheel_angle": 3.422, "front_wheel_angle": 0.16490954727140333, "heading_rate": 0.3100889496766019, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059865.8293815}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.422, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059865.8293815}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059865.9295337, "x": -88.23533320690095, "y": 40.09279088461123, "z": 202.4398235949457, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.038838816221562, "steering_wheel_angle": 3.423, "front_wheel_angle": 0.1649602412103384, "heading_rate": 0.3179894456149177, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059865.9294198}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.423, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059865.9294198}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059866.0295525, "x": -88.23533320690095, "y": 40.09279088461123, "z": 202.4398235949457, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": 3.42, "front_wheel_angle": 0.16480816424794517, "heading_rate": 0.31899026129739694, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059866.0294387}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.42, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059866.0294387}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059866.129692, "x": -88.23535931979784, "y": 40.09279422003887, "z": 202.43872691124687, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.025617816221562, "steering_wheel_angle": 3.409, "front_wheel_angle": 0.16425067326406304, "heading_rate": 0.3107697296680709, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059866.129598}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.8, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.409, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059866.129598}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059866.2295842, "x": -88.23535931979784, "y": 40.09279422003887, "z": 202.43872691124687, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": 3.385, "front_wheel_angle": 0.16303500781227973, "heading_rate": 0.32063682755676914, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059866.2294137}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.385, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059866.2294137}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059866.3295376, "x": -88.23535931979784, "y": 40.09279422003887, "z": 202.43872691124687, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": 3.298, "front_wheel_angle": 0.1586359908102129, "heading_rate": 0.30683709199501175, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059866.3293886}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.298, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059866.3293886}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059866.4295106, "x": -88.23535931979784, "y": 40.09279422003887, "z": 202.43872691124687, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": 3.142, "front_wheel_angle": 0.15077834322428268, "heading_rate": 0.29139974237952465, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059866.4294124}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.142, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059866.4294124}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059866.5294764, "x": -88.23535931979784, "y": 40.09279422003887, "z": 202.43872691124687, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": 2.876, "front_wheel_angle": 0.13746818786160925, "heading_rate": 0.2696563234981393, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059866.5293834}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059866.5293834}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059866.6296182, "x": -88.2353869587411, "y": 40.09279453782, "z": 202.43078347911487, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": 2.52, "front_wheel_angle": 0.11982432856920079, "heading_rate": 0.23092557680377254, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059866.6293206}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.52, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059866.6293206}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059866.7294674, "x": -88.2353869587411, "y": 40.09279453782, "z": 202.43078347911487, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": 2.152, "front_wheel_angle": 0.10178389409270719, "heading_rate": 0.20227883806351651, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059866.729382}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059866.729382}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059866.8295186, "x": -88.2353869587411, "y": 40.09279453782, "z": 202.43078347911487, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": 1.85, "front_wheel_angle": 0.08712491912922606, "heading_rate": 0.16752697210526712, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059866.8293872}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.85, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059866.8293872}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059866.929625, "x": -88.2353869587411, "y": 40.09279453782, "z": 202.43078347911487, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": 1.603, "front_wheel_angle": 0.07523083754525545, "heading_rate": 0.14927404349412254, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059866.9294338}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.603, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059866.9294338}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059867.0295432, "x": -88.2353869587411, "y": 40.09279453782, "z": 202.43078347911487, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": 1.419, "front_wheel_angle": 0.06642498535886315, "heading_rate": 0.13174643206788314, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059867.0294206}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.419, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059867.0294206}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059867.1295109, "x": -88.23541551670111, "y": 40.09279295350468, "z": 202.43418093493113, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": 1.276, "front_wheel_angle": 0.05961293000725829, "heading_rate": 0.11820159588516366, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059867.1293857}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.276, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059867.1293857}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059867.229626, "x": -88.23541551670111, "y": 40.09279295350468, "z": 202.43418093493113, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": 1.157, "front_wheel_angle": 0.0539649777582686, "heading_rate": 0.10697982176272197, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059867.2294264}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.157, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059867.2294264}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059867.329611, "x": -88.23541551670111, "y": 40.09279295350468, "z": 202.43418093493113, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": 1.075, "front_wheel_angle": 0.05008401282648078, "heading_rate": 0.09770640639657066, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059867.3294315}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.075, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059867.3294315}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059867.429492, "x": -88.23541551670111, "y": 40.09279295350468, "z": 202.43418093493113, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": 1.022, "front_wheel_angle": 0.047580283271626986, "heading_rate": 0.09430243811830819, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059867.4294076}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.022, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059867.4294076}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059867.5295339, "x": -88.23541551670111, "y": 40.09279295350468, "z": 202.43418093493113, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": 0.98, "front_wheel_angle": 0.04559880326936155, "heading_rate": 0.09036964731845888, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059867.5294266}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.98, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059867.5294266}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059867.6295812, "x": -88.23544433113358, "y": 40.0927904011534, "z": 202.43875017389712, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": 0.949, "front_wheel_angle": 0.04413775609962947, "heading_rate": 0.08609005423727513, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059867.629416}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.949, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059867.629416}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059867.72973, "x": -88.23544433113358, "y": 40.0927904011534, "z": 202.43875017389712, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": 0.897, "front_wheel_angle": 0.04168976842853566, "heading_rate": 0.0826131506791645, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059867.7294679}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.897, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059867.7294679}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059867.8294675, "x": -88.23544433113358, "y": 40.0927904011534, "z": 202.43875017389712, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": 0.753, "front_wheel_angle": 0.03492892947343076, "heading_rate": 0.0692037991554113, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059867.8293786}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.753, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059867.8293786}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059867.9295979, "x": -88.23544433113358, "y": 40.0927904011534, "z": 202.43875017389712, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": 0.494, "front_wheel_angle": 0.022835300116420734, "heading_rate": 0.043805006338655035, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059867.9294171}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.494, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059867.9294171}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059868.0295079, "x": -88.23544433113358, "y": 40.0927904011534, "z": 202.43875017389712, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": 0.2, "front_wheel_angle": 0.009209034229133432, "heading_rate": 0.01766313918720889, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059868.0293844}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059868.0293844}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059868.12956, "x": -88.23547291329595, "y": 40.09278671977873, "z": 202.42885583392302, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": -0.044, "front_wheel_angle": -0.002021831861724432, "heading_rate": -0.003877815612460045, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059868.129421}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.044, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059868.129421}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059868.2294629, "x": -88.23547291329595, "y": 40.09278671977873, "z": 202.42885583392302, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": -0.203, "front_wheel_angle": -0.009347539997798858, "heading_rate": -0.01760017776909286, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059868.2293806}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.203, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059868.2293806}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059868.3301544, "x": -88.23547291329595, "y": 40.09278671977873, "z": 202.42885583392302, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": -0.32, "front_wheel_angle": -0.01475787342039404, "heading_rate": -0.027327108934750242, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059868.3296816}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.32, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059868.3296816}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059868.42968, "x": -88.23547291329595, "y": 40.09278671977873, "z": 202.42885583392302, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": -0.386, "front_wheel_angle": -0.01781729857003988, "heading_rate": -0.034733487977730924, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059868.4294405}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.386, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059868.4294405}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059868.5296223, "x": -88.23547291329595, "y": 40.09278671977873, "z": 202.42885583392302, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": -0.408, "front_wheel_angle": -0.01883830640598264, "heading_rate": -0.03613555770784806, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059868.5294077}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059868.5294077}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059868.629656, "x": -88.23550127840487, "y": 40.092783312769555, "z": 202.45622631438235, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": -0.46, "front_wheel_angle": -0.02125399063470752, "heading_rate": -0.04002330602767786, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059868.6295545}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.46, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059868.6295545}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059868.7297199, "x": -88.23550127840487, "y": 40.092783312769555, "z": 202.45622631438235, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": -0.564, "front_wheel_angle": -0.026095496752448464, "heading_rate": -0.04914408328224844, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059868.7295969}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.564, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059868.7295969}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059868.8297367, "x": -88.23550127840487, "y": 40.092783312769555, "z": 202.45622631438235, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": -0.689, "front_wheel_angle": -0.031932637198262906, "heading_rate": -0.06126662605687047, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059868.8296435}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.689, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059868.8296435}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059868.9295306, "x": -88.23550127840487, "y": 40.092783312769555, "z": 202.45622631438235, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": -0.878, "front_wheel_angle": -0.040796184454574155, "heading_rate": -0.0768542076618869, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059868.9293914}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.878, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059868.9293914}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059869.0295117, "x": -88.23550127840487, "y": 40.092783312769555, "z": 202.45622631438235, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": -1.134, "front_wheel_angle": -0.05287552044577301, "heading_rate": -0.09799367209606812, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059869.0294132}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.134, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059869.0294132}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059869.129607, "x": -88.23552945102193, "y": 40.092781011486444, "z": 202.43597836905755, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": -1.409, "front_wheel_angle": -0.06594772334553617, "heading_rate": -0.12434751683667103, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059869.1294544}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.409, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059869.1294544}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059869.2294664, "x": -88.23552945102193, "y": 40.092781011486444, "z": 202.43597836905755, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": -1.691, "front_wheel_angle": -0.07945871139762747, "heading_rate": -0.14743318331774052, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059869.2293787}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.691, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059869.2293787}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059869.3294709, "x": -88.23552945102193, "y": 40.092781011486444, "z": 202.43597836905755, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": -1.759, "front_wheel_angle": -0.08273303478405086, "heading_rate": -0.15094452740694164, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059869.3293786}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.759, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059869.3293786}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059869.4295168, "x": -88.23552945102193, "y": 40.092781011486444, "z": 202.43597836905755, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": -1.635, "front_wheel_angle": -0.07676701238009531, "heading_rate": -0.14241879759654466, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059869.4294295}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.635, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059869.4294295}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059869.5295298, "x": -88.23552945102193, "y": 40.092781011486444, "z": 202.43597836905755, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": -1.47, "front_wheel_angle": -0.06886112546086101, "heading_rate": -0.1255472725049914, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059869.529416}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.47, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059869.529416}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059869.629531, "x": -88.23555730902163, "y": 40.09278003203995, "z": 202.45515914501544, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": -1.289, "front_wheel_angle": -0.060231074976767954, "heading_rate": -0.10977215394640215, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059869.629419}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059869.629419}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059869.7295053, "x": -88.23555730902163, "y": 40.09278003203995, "z": 202.45515914501544, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": -1.128, "front_wheel_angle": -0.05259142898892965, "heading_rate": -0.09582119449391, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059869.7294092}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.128, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059869.7294092}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059869.8294923, "x": -88.23555730902163, "y": 40.09278003203995, "z": 202.45515914501544, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": -1.004, "front_wheel_angle": -0.04673079578759857, "heading_rate": -0.08366522500042008, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059869.8293822}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.004, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059869.8293822}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059869.9295511, "x": -88.23555730902163, "y": 40.09278003203995, "z": 202.45515914501544, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": -0.87, "front_wheel_angle": -0.04042007806052882, "heading_rate": -0.07361726925252468, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059869.9293878}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.87, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059869.9293878}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059870.0295029, "x": -88.23555730902163, "y": 40.09278003203995, "z": 202.45515914501544, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": -0.715, "front_wheel_angle": -0.033149251355747866, "heading_rate": -0.05932781533794782, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059870.0293808}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.715, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059870.0293808}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059870.1295092, "x": -88.23558459907959, "y": 40.09278031930022, "z": 202.44802564199395, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9827178162215615, "steering_wheel_angle": -0.537, "front_wheel_angle": -0.024837263692466343, "heading_rate": -0.04366823244752728, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059870.1293874}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.537, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059870.1293874}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059870.2295084, "x": -88.23558459907959, "y": 40.09278031930022, "z": 202.44802564199395, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": -0.36, "front_wheel_angle": -0.016611426972688758, "heading_rate": -0.028618410861065317, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059870.2294073}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.36, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059870.2294073}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059870.3294802, "x": -88.23558459907959, "y": 40.09278031930022, "z": 202.44802564199395, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": -0.232, "front_wheel_angle": -0.010686996757971879, "heading_rate": -0.01841072267205729, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059870.3293786}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.232, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059870.3293786}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059870.4295697, "x": -88.23558459907959, "y": 40.09278031930022, "z": 202.44802564199395, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9592068162215615, "steering_wheel_angle": -0.161, "front_wheel_angle": -0.0074094593292757605, "heading_rate": -0.012532635167086558, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059870.429423}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059870.429423}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059870.529595, "x": -88.23558459907959, "y": 40.09278031930022, "z": 202.44802564199395, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9592068162215615, "steering_wheel_angle": -0.129, "front_wheel_angle": -0.005934269527847416, "heading_rate": -0.010037378392811994, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059870.5294845}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.129, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059870.5294845}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059870.6295428, "x": -88.23561040916205, "y": 40.092780804059416, "z": 202.44485521697737, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9376068162215616, "steering_wheel_angle": -0.124, "front_wheel_angle": -0.005703883627646137, "heading_rate": -0.009291192451342392, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059870.6293843}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.17, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.124, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059870.6293843}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059870.7295492, "x": -88.23561040916205, "y": 40.092780804059416, "z": 202.44485521697737, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9139188162215617, "steering_wheel_angle": -0.121, "front_wheel_angle": -0.005565666667536317, "heading_rate": -0.008674702853855316, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059870.7293837}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.121, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059870.7293837}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059870.8296146, "x": -88.23561040916205, "y": 40.092780804059416, "z": 202.44485521697737, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9048818162215615, "steering_wheel_angle": -0.121, "front_wheel_angle": -0.005565666667536317, "heading_rate": -0.008522515084489432, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059870.829436}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.121, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059870.829436}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059870.9295332, "x": -88.23561040916205, "y": 40.092780804059416, "z": 202.44485521697737, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.887101816221562, "steering_wheel_angle": -0.116, "front_wheel_angle": -0.005335329359043072, "heading_rate": -0.007878022008094303, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059870.9293928}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.78, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.116, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059870.9293928}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059871.0299418, "x": -88.23561040916205, "y": 40.092780804059416, "z": 202.44485521697737, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.874641816221562, "steering_wheel_angle": -0.105, "front_wheel_angle": -0.004828694110281127, "heading_rate": -0.006941301732073654, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059871.0294409}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.68, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.105, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059871.0294409}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059871.130442, "x": -88.23563352537948, "y": 40.092781233879045, "z": 202.4498477819271, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8672618162215615, "steering_wheel_angle": -0.084, "front_wheel_angle": -0.0038618888613507667, "heading_rate": -0.005460979366717382, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059871.1294947}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.084, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059871.1294947}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059871.2299073, "x": -88.23563352537948, "y": 40.092781233879045, "z": 202.4498477819271, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8443668162215614, "steering_wheel_angle": -0.069, "front_wheel_angle": -0.0031716407329421357, "heading_rate": -0.004249517262350824, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059871.229462}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.069, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059871.229462}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059871.329508, "x": -88.23563352537948, "y": 40.092781233879045, "z": 202.4498477819271, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8326068162215616, "steering_wheel_angle": -0.069, "front_wheel_angle": -0.0031716407329421357, "heading_rate": -0.004125624630795406, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059871.329384}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.069, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059871.329384}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059871.4295068, "x": -88.23563352537948, "y": 40.092781233879045, "z": 202.4498477819271, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8085618162215615, "steering_wheel_angle": -0.042, "front_wheel_angle": -0.0019298797685140421, "heading_rate": -0.002352043887889462, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059871.4293842}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.042, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059871.4293842}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059871.529563, "x": -88.23563352537948, "y": 40.092781233879045, "z": 202.4498477819271, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8302788162215617, "steering_wheel_angle": -0.02, "front_wheel_angle": -0.0009187252498868106, "heading_rate": -0.001187883372153002, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059871.5293949}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059871.5293949}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059871.6295397, "x": -88.23565278183584, "y": 40.092781557379624, "z": 202.4614994663485, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8210468162215614, "steering_wheel_angle": -0.008, "front_wheel_angle": -0.00036743230800517036, "heading_rate": -0.00046359625322873473, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059871.629405}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.008, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059871.629405}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059871.7295518, "x": -88.23565278183584, "y": 40.092781557379624, "z": 202.4614994663485, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8085618162215615, "steering_wheel_angle": -0.104, "front_wheel_angle": -0.004782643640989698, "heading_rate": -0.00582889138025641, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059871.7294223}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.104, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059871.7294223}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059871.8295481, "x": -88.23565278183584, "y": 40.092781557379624, "z": 202.4614994663485, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7952178162215615, "steering_wheel_angle": -0.476, "front_wheel_angle": -0.021997956325342807, "heading_rate": -0.025783014089760792, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059871.829418}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.476, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059871.829418}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059871.929565, "x": -88.23565278183584, "y": 40.092781557379624, "z": 202.4614994663485, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7886538162215615, "steering_wheel_angle": -1.102, "front_wheel_angle": -0.0513609140912116, "heading_rate": -0.059036720752804805, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059871.9294224}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.94, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.102, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059871.9294224}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059872.0296493, "x": -88.23565278183584, "y": 40.092781557379624, "z": 202.4614994663485, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7919268162215616, "steering_wheel_angle": -1.769, "front_wheel_angle": -0.08321509447500476, "heading_rate": -0.09676597525703509, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059872.0294702}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.769, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059872.0294702}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059872.1295109, "x": -88.23565278183584, "y": 40.092781557379624, "z": 202.4614994663485, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8210468162215614, "steering_wheel_angle": -2.319, "front_wheel_angle": -0.1099461724365061, "heading_rate": -0.1392828244476589, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059872.1293845}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.319, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059872.1293845}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059872.2294984, "x": -88.23567019787474, "y": 40.09278225202796, "z": 202.47145040093108, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.801853816221562, "steering_wheel_angle": -2.723, "front_wheel_angle": -0.12986179162520167, "heading_rate": -0.1561039275874779, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059872.2293851}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.723, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059872.2293851}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059872.329533, "x": -88.23567019787474, "y": 40.09278225202796, "z": 202.47145040093108, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8007428162215615, "steering_wheel_angle": -3.033, "front_wheel_angle": -0.14531085565617965, "heading_rate": -0.17435316246979915, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059872.3294103}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.033, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059872.3294103}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059872.429705, "x": -88.23567019787474, "y": 40.09278225202796, "z": 202.47145040093108, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7908338162215616, "steering_wheel_angle": -3.288, "front_wheel_angle": -0.15813113416354924, "heading_rate": -0.18437851484523698, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059872.4294121}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.96, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.288, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059872.4294121}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059872.529762, "x": -88.23567019787474, "y": 40.09278225202796, "z": 202.47145040093108, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8233428162215617, "steering_wheel_angle": -3.485, "front_wheel_angle": -0.16810643221999721, "heading_rate": -0.21544972299045195, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059872.5294743}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.25, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.485, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059872.5294743}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059872.62974, "x": -88.2356881333462, "y": 40.092784324381164, "z": 202.49553473100383, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7919268162215616, "steering_wheel_angle": -3.651, "front_wheel_angle": -0.1765610167453426, "heading_rate": -0.2069937775999753, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059872.6296296}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.651, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059872.6296296}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059872.729557, "x": -88.2356881333462, "y": 40.092784324381164, "z": 202.49553473100383, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8396388162215613, "steering_wheel_angle": -3.822, "front_wheel_angle": -0.18531793412348943, "heading_rate": -0.24824987089989073, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059872.729412}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.39, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.822, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059872.729412}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059872.8294709, "x": -88.2356881333462, "y": 40.092784324381164, "z": 202.49553473100383, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8119428162215616, "steering_wheel_angle": -3.981, "front_wheel_angle": -0.19350444813235387, "heading_rate": -0.2411181899547131, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059872.8293815}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.981, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059872.8293815}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059872.9297354, "x": -88.2356881333462, "y": 40.092784324381164, "z": 202.49553473100383, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8455538162215617, "steering_wheel_angle": -4.099, "front_wheel_angle": -0.1996078647932536, "heading_rate": -0.2718430697672025, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059872.92946}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.099, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059872.92946}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059873.0294654, "x": -88.2356881333462, "y": 40.092784324381164, "z": 202.49553473100383, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8372868162215616, "steering_wheel_angle": -4.19, "front_wheel_angle": -0.20433116498510187, "heading_rate": -0.27278986897440244, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059873.0293744}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.37, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.19, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059873.0293744}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059873.1295145, "x": -88.2357069472636, "y": 40.09278858668784, "z": 202.46976608513978, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8455538162215617, "steering_wheel_angle": -4.271, "front_wheel_angle": -0.20854757247805833, "heading_rate": -0.28437042504586296, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059873.1294093}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.271, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059873.1294093}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059873.2296004, "x": -88.2357069472636, "y": 40.09278858668784, "z": 202.46976608513978, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8697138162215614, "steering_wheel_angle": -4.323, "front_wheel_angle": -0.21126047961564912, "heading_rate": -0.3049360832010889, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059873.2294154}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.323, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059873.2294154}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059873.3300207, "x": -88.2357069472636, "y": 40.09278858668784, "z": 202.46976608513978, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.864817816221562, "steering_wheel_angle": -4.43, "front_wheel_angle": -0.2168578803237446, "heading_rate": -0.30982849288035125, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059873.3294535}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.6, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.43, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059873.3294535}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059873.4297185, "x": -88.2357069472636, "y": 40.09278858668784, "z": 202.46976608513978, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8858468162215614, "steering_wheel_angle": -4.496, "front_wheel_angle": -0.22032067602853278, "heading_rate": -0.32981043479995076, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059873.4294279}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.496, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059873.4294279}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059873.5296159, "x": -88.2357069472636, "y": 40.09278858668784, "z": 202.46976608513978, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8858468162215614, "steering_wheel_angle": -4.501, "front_wheel_angle": -0.22058332789188215, "heading_rate": -0.3302166548872793, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059873.5294194}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.501, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059873.5294194}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059873.6296368, "x": -88.23572693487435, "y": 40.09279559366658, "z": 202.50189863531637, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9035988162215616, "steering_wheel_angle": -4.473, "front_wheel_angle": -0.21911305673891382, "heading_rate": -0.3401215992668677, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059873.629479}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.473, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059873.629479}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059873.7296472, "x": -88.23572693487435, "y": 40.09279559366658, "z": 202.50189863531637, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9152178162215616, "steering_wheel_angle": -4.442, "front_wheel_angle": -0.21748689869292215, "heading_rate": -0.34528457423106856, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059873.7295392}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.442, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059873.7295392}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059873.8295329, "x": -88.23572693487435, "y": 40.09279559366658, "z": 202.50189863531637, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9087428162215616, "steering_wheel_angle": -4.376, "front_wheel_angle": -0.21403047927906604, "heading_rate": -0.3353791827132879, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059873.829423}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.376, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059873.829423}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059873.9296532, "x": -88.23572693487435, "y": 40.09279559366658, "z": 202.50189863531637, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.932286816221562, "steering_wheel_angle": -4.267, "front_wheel_angle": -0.2083390846714906, "heading_rate": -0.34105844433983834, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059873.92952}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.267, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059873.92952}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059874.0296412, "x": -88.23572693487435, "y": 40.09279559366658, "z": 202.50189863531637, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9204338162215615, "steering_wheel_angle": -4.133, "front_wheel_angle": -0.20137093183197832, "heading_rate": -0.32215480534480273, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059874.02939}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.04, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.133, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059874.02939}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059874.1296134, "x": -88.23574722934865, "y": 40.09280573072913, "z": 202.49456438569933, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9256818162215614, "steering_wheel_angle": -3.93, "front_wheel_angle": -0.1908739114721321, "heading_rate": -0.30795429591672513, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059874.129385}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.93, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059874.129385}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059874.229652, "x": -88.23574722934865, "y": 40.09280573072913, "z": 202.49456438569933, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9443018162215617, "steering_wheel_angle": -3.641, "front_wheel_angle": -0.17605042135075472, "heading_rate": -0.2932439717105646, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059874.2294323}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.641, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059874.2294323}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059874.3296306, "x": -88.23574722934865, "y": 40.09280573072913, "z": 202.49456438569933, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9443018162215617, "steering_wheel_angle": -3.253, "front_wheel_angle": -0.15636539305059569, "heading_rate": -0.2598800724653418, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059874.3294408}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.253, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059874.3294408}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059874.429603, "x": -88.23574722934865, "y": 40.09280573072913, "z": 202.49456438569933, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9416178162215614, "steering_wheel_angle": -2.803, "front_wheel_angle": -0.13383453495618114, "heading_rate": -0.22089271487271164, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059874.4294007}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.803, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059874.4294007}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059874.5296738, "x": -88.23574722934865, "y": 40.09280573072913, "z": 202.49456438569933, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9496938162215613, "steering_wheel_angle": -2.279, "front_wheel_angle": -0.10798744711323839, "heading_rate": -0.18039963772264278, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059874.529411}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.26, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.279, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059874.529411}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059874.6295373, "x": -88.23576647887035, "y": 40.092818177157525, "z": 202.52012612496327, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9309618162215614, "steering_wheel_angle": -1.674, "front_wheel_angle": -0.0786411310586817, "heading_rate": -0.12682462405128175, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059874.6294124}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059874.6294124}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059874.7296698, "x": -88.23576647887035, "y": 40.092818177157525, "z": 202.52012612496327, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.932286816221562, "steering_wheel_angle": -1.065, "front_wheel_angle": -0.04961132934520268, "heading_rate": -0.0801027567506848, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059874.7295787}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.065, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059874.7295787}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059874.8295786, "x": -88.23576647887035, "y": 40.092818177157525, "z": 202.52012612496327, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9402788162215616, "steering_wheel_angle": -0.549, "front_wheel_angle": -0.025396365250313788, "heading_rate": -0.041575645993922036, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059874.8293083}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.19, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.549, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059874.8293083}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059874.92982, "x": -88.23576647887035, "y": 40.092818177157525, "z": 202.52012612496327, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9389418162215613, "steering_wheel_angle": -0.192, "front_wheel_angle": -0.008839739285805979, "heading_rate": -0.014434012767249146, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059874.9294553}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.192, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059874.9294553}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059875.029588, "x": -88.23576647887035, "y": 40.092818177157525, "z": 202.52012612496327, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9217428162215615, "steering_wheel_angle": 0.057, "front_wheel_angle": 0.002619638212215624, "heading_rate": 0.004144358995650815, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059875.0293827}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.057, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059875.0293827}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059875.1295612, "x": -88.23578483663347, "y": 40.09283063040219, "z": 202.55879285396026, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9230538162215614, "steering_wheel_angle": 0.256, "front_wheel_angle": 0.011796291943346152, "heading_rate": 0.018709049565646868, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059875.1293888}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.256, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059875.1293888}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059875.2297535, "x": -88.23578483663347, "y": 40.09283063040219, "z": 202.55879285396026, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9389418162215613, "steering_wheel_angle": 0.451, "front_wheel_angle": 0.020835650355672183, "heading_rate": 0.03402563427405829, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059875.2294512}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.451, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059875.2294512}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059875.3295295, "x": -88.23578483663347, "y": 40.09283063040219, "z": 202.55879285396026, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9443018162215617, "steering_wheel_angle": 0.718, "front_wheel_angle": 0.03328968529822271, "heading_rate": 0.05489624583794739, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059875.3293867}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.718, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059875.3293867}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059875.429519, "x": -88.23578483663347, "y": 40.09283063040219, "z": 202.55879285396026, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9023178162215615, "steering_wheel_angle": 1.027, "front_wheel_angle": 0.0478163271226401, "heading_rate": 0.07290075444426733, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059875.4293861}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.9, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.027, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059875.4293861}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059875.5294805, "x": -88.23578483663347, "y": 40.09283063040219, "z": 202.55879285396026, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9362738162215614, "steering_wheel_angle": 1.323, "front_wheel_angle": 0.061848830048341685, "heading_rate": 0.10063269757070341, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059875.5293794}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.323, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059875.5293794}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059875.6295326, "x": -88.23580302784971, "y": 40.09284179021893, "z": 202.57304368255421, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8972138162215613, "steering_wheel_angle": 1.662, "front_wheel_angle": 0.07806425580663867, "heading_rate": 0.11794594673762943, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059875.629381}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.86, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.662, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059875.629381}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059875.729529, "x": -88.23580302784971, "y": 40.09284179021893, "z": 202.57304368255421, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9269988162215617, "steering_wheel_angle": 1.965, "front_wheel_angle": 0.09269172027454751, "heading_rate": 0.14851508511980763, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059875.7293873}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.09, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.965, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059875.7293873}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059875.829527, "x": -88.23580302784971, "y": 40.09284179021893, "z": 202.57304368255421, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8997618162215613, "steering_wheel_angle": 2.236, "front_wheel_angle": 0.10588441530761755, "heading_rate": 0.16108351382760036, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059875.8293934}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.88, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.236, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059875.8293934}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059875.9295173, "x": -88.23580302784971, "y": 40.09284179021893, "z": 202.57304368255421, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9204338162215615, "steering_wheel_angle": 2.546, "front_wheel_angle": 0.12110646760613769, "heading_rate": 0.1920610356828486, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059875.9293845}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.04, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.546, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059875.9293845}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059876.0295117, "x": -88.23580302784971, "y": 40.09284179021893, "z": 202.57304368255421, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9035988162215616, "steering_wheel_angle": 2.879, "front_wheel_angle": 0.13761769091770085, "heading_rate": 0.2115265500692057, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059876.029386}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.879, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059876.029386}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059876.1295042, "x": -88.23582152183242, "y": 40.09285154529706, "z": 202.5608300501254, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.919126816221562, "steering_wheel_angle": 3.126, "front_wheel_angle": 0.14997460846056065, "heading_rate": 0.23787900934123724, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059876.129386}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.126, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059876.129386}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059876.2294908, "x": -88.23582152183242, "y": 40.09285154529706, "z": 202.5608300501254, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9061668162215617, "steering_wheel_angle": 3.335, "front_wheel_angle": 0.16050535206498448, "heading_rate": 0.24853875140914386, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059876.229381}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059876.229381}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059876.3295174, "x": -88.23582152183242, "y": 40.09285154529706, "z": 202.5608300501254, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9126218162215616, "steering_wheel_angle": 3.436, "front_wheel_angle": 0.16561940974223524, "heading_rate": 0.2598668130060997, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059876.3293924}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.436, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059876.3293924}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059876.4295614, "x": -88.23582152183242, "y": 40.09285154529706, "z": 202.5608300501254, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9087428162215616, "steering_wheel_angle": 3.529, "front_wheel_angle": 0.17034300725944795, "heading_rate": 0.26540598881806754, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059876.4293954}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.529, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059876.4293954}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059876.5296261, "x": -88.23582152183242, "y": 40.09285154529706, "z": 202.5608300501254, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.919126816221562, "steering_wheel_angle": 3.693, "front_wheel_angle": 0.17870732581305654, "heading_rate": 0.28435800266139566, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059876.529418}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.693, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059876.529418}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059876.62962, "x": -88.23584128114129, "y": 40.0928592909805, "z": 202.55985458176897, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9074538162215617, "steering_wheel_angle": 3.905, "front_wheel_angle": 0.189586049322846, "heading_rate": 0.29533164236005166, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059876.6293912}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.94, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.905, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059876.6293912}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059876.7295494, "x": -88.23584128114129, "y": 40.0928592909805, "z": 202.55985458176897, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9152178162215616, "steering_wheel_angle": 4.168, "front_wheel_angle": 0.20318794883188668, "heading_rate": 0.32192365458402267, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059876.7293901}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.168, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059876.7293901}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059876.8295362, "x": -88.23584128114129, "y": 40.0928592909805, "z": 202.55985458176897, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9113268162215618, "steering_wheel_angle": 4.555, "front_wheel_angle": 0.22342284191459413, "heading_rate": 0.3523626101226133, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059876.8293855}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.555, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059876.8293855}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059876.9295266, "x": -88.23584128114129, "y": 40.0928592909805, "z": 202.55985458176897, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8997618162215613, "steering_wheel_angle": 4.966, "front_wheel_angle": 0.24520992755463675, "heading_rate": 0.37927868857220237, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059876.9293847}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.88, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.966, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059876.9293847}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059877.0294876, "x": -88.23584128114129, "y": 40.0928592909805, "z": 202.55985458176897, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9010388162215617, "steering_wheel_angle": 5.346, "front_wheel_angle": 0.2656376231809491, "heading_rate": 0.4134146978497677, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059877.029376}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.346, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059877.029376}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059877.1295125, "x": -88.23586199588256, "y": 40.09286418375693, "z": 202.5708376826519, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8959428162215617, "steering_wheel_angle": 5.706, "front_wheel_angle": 0.2852524129737268, "heading_rate": 0.44102005960546226, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059877.129404}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.706, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059877.129404}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059877.2295227, "x": -88.23586199588256, "y": 40.09286418375693, "z": 202.5708376826519, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.887101816221562, "steering_wheel_angle": 6.089, "front_wheel_angle": 0.3064123398633443, "heading_rate": 0.4671492920490518, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059877.2294044}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.78, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.089, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059877.2294044}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059877.3296878, "x": -88.23586199588256, "y": 40.09286418375693, "z": 202.5708376826519, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8972138162215613, "steering_wheel_angle": 6.441, "front_wheel_angle": 0.3261362859113151, "heading_rate": 0.5099625943188356, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059877.3294294}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.86, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.441, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059877.3294294}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059877.4295459, "x": -88.23586199588256, "y": 40.09286418375693, "z": 202.5708376826519, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9035988162215616, "steering_wheel_angle": 6.731, "front_wheel_angle": 0.34259334994129603, "heading_rate": 0.5447384798469349, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059877.4294147}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.731, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059877.4294147}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059877.5295365, "x": -88.23586199588256, "y": 40.09286418375693, "z": 202.5708376826519, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8959428162215617, "steering_wheel_angle": 6.978, "front_wheel_angle": 0.3567631873215652, "heading_rate": 0.5605238072292017, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059877.529387}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.978, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059877.529387}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059877.6295211, "x": -88.23588223768388, "y": 40.09286492171012, "z": 202.56445413786827, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.887101816221562, "steering_wheel_angle": 7.168, "front_wheel_angle": 0.3677616920129659, "heading_rate": 0.5689052924182484, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059877.6293929}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.78, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.168, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059877.6293929}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059877.7295344, "x": -88.23588223768388, "y": 40.09286492171012, "z": 202.56445413786827, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8820938162215617, "steering_wheel_angle": 7.477, "front_wheel_angle": 0.3858376835882731, "heading_rate": 0.5934292927101679, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059877.7293844}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.477, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059877.7293844}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059877.8294957, "x": -88.23588223768388, "y": 40.09286492171012, "z": 202.56445413786827, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8734068162215616, "steering_wheel_angle": 7.91, "front_wheel_angle": 0.4115772263660529, "heading_rate": 0.6257746584703812, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059877.8294032}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.91, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059877.8294032}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059877.9295306, "x": -88.23588223768388, "y": 40.09286492171012, "z": 202.56445413786827, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8721738162215615, "steering_wheel_angle": 8.37, "front_wheel_angle": 0.4394742123202507, "heading_rate": 0.6721509450067773, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059877.9294064}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.37, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059877.9294064}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059878.0295718, "x": -88.23588223768388, "y": 40.09286492171012, "z": 202.56445413786827, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.887101816221562, "steering_wheel_angle": 8.761, "front_wheel_angle": 0.46366115008775205, "heading_rate": 0.7383062429957097, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059878.0294054}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.78, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.761, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059878.0294054}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059878.1295242, "x": -88.2359003394512, "y": 40.0928610806619, "z": 202.58479486287132, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8934068162215616, "steering_wheel_angle": 9.041, "front_wheel_angle": 0.48126435145452967, "heading_rate": 0.7812884912587412, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059878.1293874}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059878.1293874}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059878.229513, "x": -88.2359003394512, "y": 40.0928610806619, "z": 202.58479486287132, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8921418162215615, "steering_wheel_angle": 9.307, "front_wheel_angle": 0.4982161163294084, "heading_rate": 0.8117327878415563, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059878.2293816}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059878.2293816}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059878.3295166, "x": -88.2359003394512, "y": 40.0928610806619, "z": 202.58479486287132, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.858742816221562, "steering_wheel_angle": 9.501, "front_wheel_angle": 0.5107253018907255, "heading_rate": 0.7769942385430018, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059878.329382}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.55, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.501, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059878.329382}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059878.429665, "x": -88.2359003394512, "y": 40.0928610806619, "z": 202.58479486287132, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8479338162215617, "steering_wheel_angle": 9.622, "front_wheel_angle": 0.5185916114590025, "heading_rate": 0.7713275814135326, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059878.4294665}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.622, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059878.4294665}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059878.5295763, "x": -88.2359003394512, "y": 40.0928610806619, "z": 202.58479486287132, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8623818162215615, "steering_wheel_angle": 9.741, "front_wheel_angle": 0.5263771019583965, "heading_rate": 0.8125770245634292, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059878.529388}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.741, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059878.529388}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059878.6294715, "x": -88.2359151575392, "y": 40.09285353211623, "z": 202.62188230648752, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8934068162215616, "steering_wheel_angle": 9.846, "front_wheel_angle": 0.5332879218626143, "heading_rate": 0.8832072979030164, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059878.6293755}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.846, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059878.6293755}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059878.7294707, "x": -88.2359151575392, "y": 40.09285353211623, "z": 202.62188230648752, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8984868162215616, "steering_wheel_angle": 9.884, "front_wheel_angle": 0.5357986502212391, "heading_rate": 0.897557270374833, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059878.7293723}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.884, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059878.7293723}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059878.8295622, "x": -88.2359151575392, "y": 40.09285353211623, "z": 202.62188230648752, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8419988162215617, "steering_wheel_angle": 9.894, "front_wheel_angle": 0.5364602294523477, "heading_rate": 0.7920632444194748, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059878.829434}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.894, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059878.829434}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059878.92959, "x": -88.2359151575392, "y": 40.09285353211623, "z": 202.62188230648752, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8972138162215613, "steering_wheel_angle": 9.898, "front_wheel_angle": 0.5367249619070992, "heading_rate": 0.8971281099480268, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059878.9294202}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.86, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.898, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059878.9294202}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059879.0296001, "x": -88.2359151575392, "y": 40.09285353211623, "z": 202.62188230648752, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8419988162215617, "steering_wheel_angle": 9.898, "front_wheel_angle": 0.5367249619070992, "heading_rate": 0.7925406359903554, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059879.0293941}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.898, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059879.0293941}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059879.1296453, "x": -88.23592580541798, "y": 40.092843142594035, "z": 202.68421588268913, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8959428162215617, "steering_wheel_angle": 9.898, "front_wheel_angle": 0.5367249619070992, "heading_rate": 0.8948039438600787, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059879.129437}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.898, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059879.129437}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059879.2295322, "x": -88.23592580541798, "y": 40.092843142594035, "z": 202.68421588268913, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.858742816221562, "steering_wheel_angle": 9.898, "front_wheel_angle": 0.5367249619070992, "heading_rate": 0.8250789612216308, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059879.2294073}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.55, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.898, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059879.2294073}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059879.329543, "x": -88.23592580541798, "y": 40.092843142594035, "z": 202.68421588268913, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8896178162215618, "steering_wheel_angle": 9.898, "front_wheel_angle": 0.5367249619070992, "heading_rate": 0.8831831134203372, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059879.3294168}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.8, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.898, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059879.3294168}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059879.4295151, "x": -88.23592580541798, "y": 40.092843142594035, "z": 202.68421588268913, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8721738162215615, "steering_wheel_angle": 9.898, "front_wheel_angle": 0.5367249619070992, "heading_rate": 0.8506447881890618, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059879.4294026}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.898, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059879.4294026}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059879.5294986, "x": -88.23592580541798, "y": 40.092843142594035, "z": 202.68421588268913, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8758788162215616, "steering_wheel_angle": 9.898, "front_wheel_angle": 0.5367249619070992, "heading_rate": 0.8576172864529065, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059879.529396}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.898, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059879.529396}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059879.6295698, "x": -88.2359310848837, "y": 40.0928306230877, "z": 202.68620575709673, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8672618162215615, "steering_wheel_angle": 9.898, "front_wheel_angle": 0.5367249619070992, "heading_rate": 0.8413481238372689, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059879.6294062}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.898, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059879.6294062}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059879.7295485, "x": -88.2359310848837, "y": 40.0928306230877, "z": 202.68620575709673, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8672618162215615, "steering_wheel_angle": 9.898, "front_wheel_angle": 0.5367249619070992, "heading_rate": 0.8413481238372689, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059879.7294116}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.898, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059879.7294116}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059879.829547, "x": -88.2359310848837, "y": 40.0928306230877, "z": 202.68620575709673, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.858742816221562, "steering_wheel_angle": 9.898, "front_wheel_angle": 0.5367249619070992, "heading_rate": 0.8250789612216308, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059879.829414}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.55, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.898, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059879.829414}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059879.9295573, "x": -88.2359310848837, "y": 40.0928306230877, "z": 202.68620575709673, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8551218162215615, "steering_wheel_angle": 9.896, "front_wheel_angle": 0.5365925884777173, "heading_rate": 0.8178600345026666, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059879.9294229}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.896, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059879.9294229}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059880.0295084, "x": -88.2359310848837, "y": 40.0928306230877, "z": 202.68620575709673, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8467428162215613, "steering_wheel_angle": 9.894, "front_wheel_angle": 0.5364602294523477, "heading_rate": 0.8013543088701433, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059880.0293832}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.45, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.894, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059880.0293832}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059880.1295402, "x": -88.2359300598526, "y": 40.092817486923686, "z": 202.73680003281922, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8455538162215617, "steering_wheel_angle": 9.893, "front_wheel_angle": 0.5363940553396983, "heading_rate": 0.7989111849463847, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059880.129409}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.893, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059880.129409}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059880.2294714, "x": -88.2359300598526, "y": 40.092817486923686, "z": 202.73680003281922, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8337738162215613, "steering_wheel_angle": 9.893, "front_wheel_angle": 0.5363940553396983, "heading_rate": 0.7756870225932919, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059880.2293732}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.893, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059880.2293732}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059880.329474, "x": -88.2359300598526, "y": 40.092817486923686, "z": 202.73680003281922, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8142068162215614, "steering_wheel_angle": 9.891, "front_wheel_angle": 0.5362617179115338, "heading_rate": 0.7359841686196195, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059880.329373}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.17, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.891, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059880.329373}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059880.4295623, "x": -88.2359300598526, "y": 40.092817486923686, "z": 202.73680003281922, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8029668162215615, "steering_wheel_angle": 9.883, "front_wheel_angle": 0.5357325120745877, "heading_rate": 0.7119084461650755, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059880.4294233}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.883, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059880.4294233}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059880.529507, "x": -88.2359300598526, "y": 40.092817486923686, "z": 202.73680003281922, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7810868162215616, "steering_wheel_angle": 9.85, "front_wheel_angle": 0.533551965621554, "heading_rate": 0.6622282107773848, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059880.5293794}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.85, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059880.5293794}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059880.6296344, "x": -88.23592455190122, "y": 40.09280666227684, "z": 202.70154292018833, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7725588162215615, "steering_wheel_angle": 9.823, "front_wheel_angle": 0.5317707781579377, "heading_rate": 0.6411530833679996, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059880.6294255}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.79, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.823, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059880.6294255}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059880.7295673, "x": -88.23592455190122, "y": 40.09280666227684, "z": 202.70154292018833, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7736178162215617, "steering_wheel_angle": 9.827, "front_wheel_angle": 0.5320344938159788, "heading_rate": 0.643839449569651, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059880.729425}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.8, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.827, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059880.729425}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059880.8298514, "x": -88.23592455190122, "y": 40.09280666227684, "z": 202.70154292018833, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7736178162215617, "steering_wheel_angle": 9.843, "front_wheel_angle": 0.5330899265494695, "heading_rate": 0.6453948030788155, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059880.8294756}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.8, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.843, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059880.8294756}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059880.9295259, "x": -88.23592455190122, "y": 40.09280666227684, "z": 202.70154292018833, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7683428162215615, "steering_wheel_angle": 9.905, "front_wheel_angle": 0.537188382409465, "heading_rate": 0.6398199060985483, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059880.9293787}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.75, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.905, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059880.9293787}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059881.0294552, "x": -88.23592455190122, "y": 40.09280666227684, "z": 202.70154292018833, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7631178162215617, "steering_wheel_angle": 9.972, "front_wheel_angle": 0.5416329480127606, "heading_rate": 0.6345543081159714, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059881.0293684}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.7, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.972, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059881.0293684}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059881.1295936, "x": -88.23591684738525, "y": 40.09279825280365, "z": 202.64756298422745, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7569138162215614, "steering_wheel_angle": 9.979, "front_wheel_angle": 0.5420982468694603, "heading_rate": 0.6211068182192534, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059881.129391}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.979, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059881.129391}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059881.2294838, "x": -88.23591684738525, "y": 40.09279825280365, "z": 202.64756298422745, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7672938162215615, "steering_wheel_angle": 9.979, "front_wheel_angle": 0.5420982468694603, "heading_rate": 0.6446335916366494, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059881.2293737}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.979, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059881.2293737}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059881.329508, "x": -88.23591684738525, "y": 40.09279825280365, "z": 202.64756298422745, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7569138162215614, "steering_wheel_angle": 9.979, "front_wheel_angle": 0.5420982468694603, "heading_rate": 0.6211068182192534, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059881.3293793}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.979, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059881.3293793}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059881.4295385, "x": -88.23591684738525, "y": 40.09279825280365, "z": 202.64756298422745, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7746788162215617, "steering_wheel_angle": 9.978, "front_wheel_angle": 0.5420317646579869, "heading_rate": 0.6610028910216216, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059881.4294088}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.81, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.978, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059881.4294088}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059881.5295002, "x": -88.23591684738525, "y": 40.09279825280365, "z": 202.64756298422745, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7725588162215615, "steering_wheel_angle": 9.977, "front_wheel_angle": 0.5419652860962585, "heading_rate": 0.6561995232005735, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059881.5293756}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.79, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.977, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059881.5293756}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059881.6294713, "x": -88.2359072071004, "y": 40.092791488418044, "z": 202.6203944942445, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7768068162215616, "steering_wheel_angle": 9.965, "front_wheel_angle": 0.5411678278170164, "heading_rate": 0.6644068192823931, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059881.6293728}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.965, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059881.6293728}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059881.729538, "x": -88.2359072071004, "y": 40.092791488418044, "z": 202.6203944942445, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7919268162215616, "steering_wheel_angle": 9.892, "front_wheel_angle": 0.5363278848262896, "heading_rate": 0.6896537221390509, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059881.7293856}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.892, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059881.7293856}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059881.8294935, "x": -88.2359072071004, "y": 40.092791488418044, "z": 202.6203944942445, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7952178162215615, "steering_wheel_angle": 9.71, "front_wheel_angle": 0.5243441970296249, "heading_rate": 0.6777475693848858, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059881.8293953}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.71, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059881.8293953}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059881.9294693, "x": -88.2359072071004, "y": 40.092791488418044, "z": 202.6203944942445, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8176178162215617, "steering_wheel_angle": 9.451, "front_wheel_angle": 0.5074892673393235, "heading_rate": 0.6950837942673033, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059881.92937}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.451, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059881.92937}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059882.0295177, "x": -88.2359072071004, "y": 40.092791488418044, "z": 202.6203944942445, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8291178162215616, "steering_wheel_angle": 9.039, "front_wheel_angle": 0.48113775036918993, "heading_rate": 0.6729651626916644, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059882.02941}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.039, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059882.02941}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059882.1295187, "x": -88.2359072071004, "y": 40.092791488418044, "z": 202.6203944942445, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8384618162215616, "steering_wheel_angle": 8.287, "front_wheel_angle": 0.4343969852961064, "heading_rate": 0.6125637755116361, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059882.1293793}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.287, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059882.1293793}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059882.22975, "x": -88.2358944806205, "y": 40.09278650036232, "z": 202.5945896088633, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8709428162215618, "steering_wheel_angle": 7.436, "front_wheel_angle": 0.38342552328758905, "heading_rate": 0.5751461518882938, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059882.2293966}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.436, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059882.2293966}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059882.3295355, "x": -88.2358944806205, "y": 40.09278650036232, "z": 202.5945896088633, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8783588162215614, "steering_wheel_angle": 6.678, "front_wheel_angle": 0.3395713696632013, "heading_rate": 0.5119433150048971, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059882.3294106}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.71, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.678, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059882.3294106}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059882.4295125, "x": -88.2358944806205, "y": 40.09278650036232, "z": 202.5945896088633, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9204338162215615, "steering_wheel_angle": 6.001, "front_wheel_angle": 0.3015232325268311, "heading_rate": 0.49080638585460706, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059882.4293804}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.04, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.001, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059882.4293804}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059882.529474, "x": -88.2358944806205, "y": 40.09278650036232, "z": 202.5945896088633, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9429588162215614, "steering_wheel_angle": 5.274, "front_wheel_angle": 0.2617456250818251, "heading_rate": 0.4405560593882732, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059882.529371}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.21, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.274, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059882.529371}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059882.6296449, "x": -88.23587617703292, "y": 40.09278224943853, "z": 202.59333505274088, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9633138162215618, "steering_wheel_angle": 4.669, "front_wheel_angle": 0.22943475063214938, "heading_rate": 0.39776008026406634, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059882.629383}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.669, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059882.629383}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059882.729474, "x": -88.23587617703292, "y": 40.09278224943853, "z": 202.59333505274088, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9953988162215617, "steering_wheel_angle": 4.326, "front_wheel_angle": 0.21141713915445792, "heading_rate": 0.38481486436692447, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059882.7293825}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.59, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.326, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059882.7293825}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059882.8294802, "x": -88.23587617703292, "y": 40.09278224943853, "z": 202.59333505274088, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.022701816221562, "steering_wheel_angle": 4.022, "front_wheel_angle": 0.195622415116399, "heading_rate": 0.36999549159920975, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059882.8293717}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.78, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.022, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059882.8293717}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059882.9295442, "x": -88.23587617703292, "y": 40.09278224943853, "z": 202.59333505274088, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": 3.609, "front_wheel_angle": 0.1744176259320921, "heading_rate": 0.34897463369404524, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059882.9294062}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.609, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059882.9294062}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059883.0296617, "x": -88.23587617703292, "y": 40.09278224943853, "z": 202.59333505274088, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": 3.128, "front_wheel_angle": 0.15007505326627996, "heading_rate": 0.30892136314968494, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059883.029433}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.128, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059883.029433}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059883.1296155, "x": -88.23585049433248, "y": 40.09277919154632, "z": 202.56826870093144, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": 2.591, "front_wheel_angle": 0.1233279382016879, "heading_rate": 0.2571139946411257, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059883.129399}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.591, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059883.129399}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059883.229468, "x": -88.23585049433248, "y": 40.09277919154632, "z": 202.56826870093144, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.142353816221561, "steering_wheel_angle": 2.078, "front_wheel_angle": 0.0981799486220276, "heading_rate": 0.2139223721658081, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059883.2293687}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.078, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059883.2293687}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059883.3294752, "x": -88.23585049433248, "y": 40.09277919154632, "z": 202.56826870093144, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": 1.683, "front_wheel_angle": 0.07907391796534274, "heading_rate": 0.17704995186343933, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059883.3293695}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.683, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059883.3293695}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059883.4295113, "x": -88.23585049433248, "y": 40.09277919154632, "z": 202.56826870093144, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1966388162215615, "steering_wheel_angle": 1.374, "front_wheel_angle": 0.06427836851278046, "heading_rate": 0.14809448234242853, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059883.4294116}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.374, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059883.4294116}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059883.5295627, "x": -88.23585049433248, "y": 40.09277919154632, "z": 202.56826870093144, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.223742816221561, "steering_wheel_angle": 1.108, "front_wheel_angle": 0.05164480007450787, "heading_rate": 0.12215981461640936, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059883.5294275}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.108, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059883.5294275}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059883.6294787, "x": -88.23581802583875, "y": 40.0927773898081, "z": 202.5769521017487, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.267117816221561, "steering_wheel_angle": 0.836, "front_wheel_angle": 0.03882254652525654, "heading_rate": 0.0955878884558309, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059883.6293716}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.836, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059883.6293716}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059883.7299778, "x": -88.23581802583875, "y": 40.0927773898081, "z": 202.5769521017487, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": 0.602, "front_wheel_angle": 0.02786789797492743, "heading_rate": 0.07034110917020996, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059883.7294433}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.602, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059883.7294433}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059883.8294742, "x": -88.23581802583875, "y": 40.0927773898081, "z": 202.5769521017487, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": 0.461, "front_wheel_angle": 0.02130047912639609, "heading_rate": 0.05375855831397443, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059883.829368}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.461, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059883.829368}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059883.9295702, "x": -88.23581802583875, "y": 40.0927773898081, "z": 202.5769521017487, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.324461816221562, "steering_wheel_angle": 0.394, "front_wheel_angle": 0.018188504619623874, "heading_rate": 0.04703952351093184, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059883.9294653}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.394, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059883.9294653}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059884.029525, "x": -88.23581802583875, "y": 40.0927773898081, "z": 202.5769521017487, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.355758816221561, "steering_wheel_angle": 0.329, "front_wheel_angle": 0.015174750598687906, "heading_rate": 0.04025174458641174, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059884.0293977}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.329, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059884.0293977}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059884.1294992, "x": -88.23578044124153, "y": 40.092776092196914, "z": 202.56778033958278, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": 0.284, "front_wheel_angle": 0.013091363545958393, "heading_rate": 0.03513390854142372, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059884.1293972}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.284, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059884.1293972}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059884.2294524, "x": -88.23578044124153, "y": 40.092776092196914, "z": 202.56778033958278, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.400926816221562, "steering_wheel_angle": 0.232, "front_wheel_angle": 0.010686996757971879, "heading_rate": 0.0293486123321004, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059884.2293634}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.232, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059884.2293634}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059884.329484, "x": -88.23578044124153, "y": 40.092776092196914, "z": 202.56778033958278, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": 0.163, "front_wheel_angle": 0.007501700088116369, "heading_rate": 0.02086449475819624, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059884.3293877}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059884.3293877}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059884.4294658, "x": -88.23578044124153, "y": 40.092776092196914, "z": 202.56778033958278, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.449201816221562, "steering_wheel_angle": 0.104, "front_wheel_angle": 0.004782643640989698, "heading_rate": 0.013600746553931625, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059884.429367}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.104, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059884.429367}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059884.5295362, "x": -88.23578044124153, "y": 40.092776092196914, "z": 202.56778033958278, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.464913816221562, "steering_wheel_angle": 0.041, "front_wheel_angle": 0.0018839055326036736, "heading_rate": 0.005416234813823504, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059884.5294046}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059884.5294046}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059884.6295073, "x": -88.23573906504234, "y": 40.092775292499, "z": 202.58573876223818, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.480753816221561, "steering_wheel_angle": -0.025, "front_wheel_angle": -0.0011484818458397522, "heading_rate": -0.003337776831992861, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059884.6293747}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059884.6293747}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059884.7295656, "x": -88.23573906504234, "y": 40.092775292499, "z": 202.58573876223818, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.496721816221561, "steering_wheel_angle": -0.029, "front_wheel_angle": -0.0013323088207378546, "heading_rate": -0.003913659476560623, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059884.7293725}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.029, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059884.7293725}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059884.829566, "x": -88.23573906504234, "y": 40.092775292499, "z": 202.58573876223818, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.514838816221562, "steering_wheel_angle": -0.029, "front_wheel_angle": -0.0013323088207378546, "heading_rate": -0.003960498486253503, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059884.8294165}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.029, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059884.8294165}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059884.9296403, "x": -88.23573906504234, "y": 40.092775292499, "z": 202.58573876223818, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.531078816221561, "steering_wheel_angle": -0.021, "front_wheel_angle": -0.0009646741586794069, "heading_rate": -0.0028977916333619434, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059884.9294746}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.021, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059884.9294746}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059885.0295231, "x": -88.23573906504234, "y": 40.092775292499, "z": 202.58573876223818, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.547446816221561, "steering_wheel_angle": -0.013, "front_wheel_angle": -0.0005971166232941916, "heading_rate": -0.0018123424665661182, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059885.0294027}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059885.0294027}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059885.129521, "x": -88.23569484772914, "y": 40.09277457787323, "z": 202.57750163984315, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.580566816221562, "steering_wheel_angle": 0.002, "front_wheel_angle": 9.1850856414927e-05, "heading_rate": 0.0002845223802416831, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059885.129398}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.002, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059885.129398}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059885.2295241, "x": -88.23569484772914, "y": 40.09277457787323, "z": 202.57750163984315, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.580566816221562, "steering_wheel_angle": 0.04, "front_wheel_angle": 0.0018379325036962971, "heading_rate": 0.00569328951779062, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059885.2293766}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.04, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059885.2293766}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059885.329575, "x": -88.23569484772914, "y": 40.09277457787323, "z": 202.57750163984315, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": 0.08, "front_wheel_angle": 0.003677796062834341, "heading_rate": 0.011636829072405697, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059885.3294299}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.08, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059885.3294299}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059885.429533, "x": -88.23569484772914, "y": 40.09277457787323, "z": 202.57750163984315, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": 0.097, "front_wheel_angle": 0.0044603243150626555, "heading_rate": 0.014112838492507572, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059885.4293854}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.097, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059885.4293854}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059885.5298407, "x": -88.23569484772914, "y": 40.09277457787323, "z": 202.57750163984315, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.633341816221561, "steering_wheel_angle": 0.095, "front_wheel_angle": 0.004368243991637956, "heading_rate": 0.013957993409719226, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059885.5294702}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.095, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059885.5294702}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059885.6295028, "x": -88.23564834297768, "y": 40.09277404167607, "z": 202.60228718244477, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.650493816221561, "steering_wheel_angle": 0.094, "front_wheel_angle": 0.004322205648206082, "heading_rate": 0.013945953505496694, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059885.629373}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.26, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.094, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059885.629373}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059885.7294772, "x": -88.23564834297768, "y": 40.09277404167607, "z": 202.60228718244477, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.667773816221562, "steering_wheel_angle": 0.093, "front_wheel_angle": 0.004276168516833251, "heading_rate": 0.013931040158905115, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059885.7293668}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.093, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059885.7293668}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059885.8294597, "x": -88.23564834297768, "y": 40.09277404167607, "z": 202.60228718244477, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.687366816221561, "steering_wheel_angle": 0.093, "front_wheel_angle": 0.004276168516833251, "heading_rate": 0.014081375124648694, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059885.829366}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.093, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059885.829366}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059885.92955, "x": -88.23564834297768, "y": 40.09277404167607, "z": 202.60228718244477, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.687366816221561, "steering_wheel_angle": 0.091, "front_wheel_angle": 0.004184097889882324, "heading_rate": 0.013778184001814443, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059885.929397}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.091, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059885.929397}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059886.0295484, "x": -88.23564834297768, "y": 40.09277404167607, "z": 202.60228718244477, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.704918816221562, "steering_wheel_angle": 0.09, "front_wheel_angle": 0.0041380643941128885, "heading_rate": 0.013755909764500114, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059886.0293667}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.51, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.09, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059886.0293667}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059886.1295009, "x": -88.23559968380454, "y": 40.09277379115276, "z": 202.58804257842834, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.722598816221561, "steering_wheel_angle": 0.09, "front_wheel_angle": 0.0041380643941128885, "heading_rate": 0.013885225014930197, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059886.1293743}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.59, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.09, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059886.1293743}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059886.2296178, "x": -88.23559968380454, "y": 40.09277379115276, "z": 202.58804257842834, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.740406816221562, "steering_wheel_angle": 0.088, "front_wheel_angle": 0.004046001037507012, "heading_rate": 0.013702742348191653, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059886.2293818}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.088, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059886.2293818}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059886.3294876, "x": -88.23559968380454, "y": 40.09277379115276, "z": 202.58804257842834, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.740406816221562, "steering_wheel_angle": 0.084, "front_wheel_angle": 0.0038618888613507667, "heading_rate": 0.01307919643907174, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059886.3293695}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.084, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059886.3293695}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059886.4297657, "x": -88.23559968380454, "y": 40.09277379115276, "z": 202.58804257842834, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.758342816221561, "steering_wheel_angle": 0.066, "front_wheel_angle": 0.003033623778655747, "heading_rate": 0.010368863082499274, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059886.429451}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.75, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.066, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059886.429451}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059886.529673, "x": -88.23559968380454, "y": 40.09277379115276, "z": 202.58804257842834, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.776406816221561, "steering_wheel_angle": 0.031, "front_wheel_angle": 0.0014242295429861569, "heading_rate": 0.004912482565514228, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059886.5294561}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.031, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059886.5294561}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059886.6294508, "x": -88.23554925185461, "y": 40.0927737555464, "z": 202.6051951578925, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.776406816221561, "steering_wheel_angle": -0.003, "front_wheel_angle": -0.00013777808953256048, "heading_rate": -0.0004752267727619316, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059886.6293612}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.003, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059886.6293612}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059886.7294917, "x": -88.23554925185461, "y": 40.0927737555464, "z": 202.6051951578925, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.796881816221561, "steering_wheel_angle": -0.008, "front_wheel_angle": -0.00036743230800517036, "heading_rate": -0.0012802720058205305, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059886.7294}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.008, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059886.7294}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059886.8295093, "x": -88.23554925185461, "y": 40.0927737555464, "z": 202.6051951578925, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.796881816221561, "steering_wheel_angle": 0.03, "front_wheel_angle": 0.0013782685788830463, "heading_rate": 0.004802407620469365, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059886.8294044}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059886.8294044}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059886.9294953, "x": -88.23554925185461, "y": 40.0927737555464, "z": 202.6051951578925, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.815217816221562, "steering_wheel_angle": 0.232, "front_wheel_angle": 0.010686996757971879, "heading_rate": 0.03757290341236182, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059886.9293756}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.232, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059886.9293756}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059887.0295548, "x": -88.23554925185461, "y": 40.0927737555464, "z": 202.6051951578925, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.833681816221562, "steering_wheel_angle": 0.382, "front_wheel_angle": 0.017631725321869237, "heading_rate": 0.06254400706514289, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059887.0294228}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.382, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059887.0294228}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059887.1296651, "x": -88.23549770818417, "y": 40.09277379975661, "z": 202.63610177781396, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.833681816221562, "steering_wheel_angle": 0.405, "front_wheel_angle": 0.018699042669962463, "heading_rate": 0.06633089810920646, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059887.1293864}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.405, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059887.1293864}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059887.2295272, "x": -88.23549770818417, "y": 40.09277379975661, "z": 202.63610177781396, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.833681816221562, "steering_wheel_angle": 0.336, "front_wheel_angle": 0.015499057555256903, "heading_rate": 0.054977622092651696, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059887.2294147}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.336, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059887.2294147}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059887.3294764, "x": -88.23549770818417, "y": 40.09277379975661, "z": 202.63610177781396, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.852273816221562, "steering_wheel_angle": 0.28, "front_wheel_angle": 0.012906294304269457, "heading_rate": 0.046182898601862934, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059887.329365}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.28, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059887.329365}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059887.4294763, "x": -88.23549770818417, "y": 40.09277379975661, "z": 202.63610177781396, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.852273816221562, "steering_wheel_angle": 0.287, "front_wheel_angle": 0.013230178396903713, "heading_rate": 0.04734199431866474, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059887.4293633}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.287, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059887.4293633}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059887.5295, "x": -88.23549770818417, "y": 40.09277379975661, "z": 202.63610177781396, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.870993816221562, "steering_wheel_angle": 0.301, "front_wheel_angle": 0.013878127539494502, "heading_rate": 0.050094582741847624, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059887.529401}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.301, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059887.529401}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059887.6295354, "x": -88.2354449611609, "y": 40.092775038811176, "z": 202.69020407519017, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": 0.3, "front_wheel_angle": 0.013831837452108262, "heading_rate": 0.05041377893028224, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059887.6293864}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059887.6293864}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059887.729544, "x": -88.2354449611609, "y": 40.092775038811176, "z": 202.69020407519017, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": 0.297, "front_wheel_angle": 0.013692974581860034, "heading_rate": 0.04990759299188692, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059887.7294352}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.297, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059887.7294352}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059887.8295724, "x": -88.2354449611609, "y": 40.092775038811176, "z": 202.69020407519017, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.870993816221562, "steering_wheel_angle": 0.278, "front_wheel_angle": 0.012813767064331754, "heading_rate": 0.04625222195013156, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059887.829384}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.278, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059887.829384}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059887.9294655, "x": -88.2354449611609, "y": 40.092775038811176, "z": 202.69020407519017, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": 0.209, "front_wheel_angle": 0.009624584547123486, "heading_rate": 0.03507818228501429, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059887.929361}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.209, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059887.929361}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059888.029505, "x": -88.2354449611609, "y": 40.092775038811176, "z": 202.69020407519017, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.870993816221562, "steering_wheel_angle": 0.12, "front_wheel_angle": 0.005519596776924772, "heading_rate": 0.01992249693637952, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059888.0293977}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.12, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059888.0293977}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059888.129498, "x": -88.23539107422854, "y": 40.09277795498668, "z": 202.67016464064307, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.870993816221562, "steering_wheel_angle": 0.082, "front_wheel_angle": 0.003769840040269683, "heading_rate": 0.013606830854114606, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059888.1293921}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.082, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059888.1293921}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059888.2294586, "x": -88.23539107422854, "y": 40.09277795498668, "z": 202.67016464064307, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.852273816221562, "steering_wheel_angle": 0.067, "front_wheel_angle": 0.0030796282205738327, "heading_rate": 0.011019329562940588, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059888.229362}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.067, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059888.229362}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059888.3294845, "x": -88.23539107422854, "y": 40.09277795498668, "z": 202.67016464064307, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.833681816221562, "steering_wheel_angle": 0.033, "front_wheel_angle": 0.0015161550894462375, "heading_rate": 0.0053776167034364905, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059888.3293905}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.033, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059888.3293905}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059888.4299562, "x": -88.23539107422854, "y": 40.09277795498668, "z": 202.67016464064307, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.815217816221562, "steering_wheel_angle": 0.01, "front_wheel_angle": 0.0004593024218401402, "heading_rate": 0.0016147351903292313, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059888.4294167}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.01, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059888.4294167}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059888.529657, "x": -88.23539107422854, "y": 40.09277795498668, "z": 202.67016464064307, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.796881816221561, "steering_wheel_angle": 0.001, "front_wheel_angle": 4.592482660220106e-05, "heading_rate": 0.00016001931780454268, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059888.529389}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.001, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059888.529389}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059888.6295054, "x": -88.23533798273091, "y": 40.09278109482429, "z": 202.6863929683651, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.722598816221561, "steering_wheel_angle": -0.028, "front_wheel_angle": -0.0012863502684559124, "heading_rate": -0.004316310508086889, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059888.6293948}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.59, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.028, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059888.6293948}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059888.7296152, "x": -88.23533798273091, "y": 40.09278109482429, "z": 202.6863929683651, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": -0.047, "front_wheel_angle": -0.0021597690564398976, "heading_rate": -0.0067661620176165315, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059888.7294211}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.047, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059888.7294211}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059888.8294716, "x": -88.23533798273091, "y": 40.09278109482429, "z": 202.6863929683651, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.464913816221562, "steering_wheel_angle": -0.052, "front_wheel_angle": -0.002389688533708352, "heading_rate": -0.006870367612416104, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059888.8293645}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.052, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059888.8293645}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059888.9295173, "x": -88.23533798273091, "y": 40.09278109482429, "z": 202.6863929683651, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": -0.059, "front_wheel_angle": -0.002711626542631913, "heading_rate": -0.007626468343428158, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059888.9293716}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.059, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059888.9293716}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059889.0295618, "x": -88.23533798273091, "y": 40.09278109482429, "z": 202.6863929683651, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.267117816221561, "steering_wheel_angle": -0.088, "front_wheel_angle": -0.004046001037507012, "heading_rate": -0.009957010010796703, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059889.0293903}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.088, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059889.0293903}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059889.129482, "x": -88.23529388718399, "y": 40.09278354450401, "z": 202.67876079608683, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.223742816221561, "steering_wheel_angle": -0.093, "front_wheel_angle": -0.004276168516833251, "heading_rate": -0.010105850474985124, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059889.12937}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.093, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059889.12937}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059889.2294807, "x": -88.23529388718399, "y": 40.09278354450401, "z": 202.67876079608683, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": -0.095, "front_wheel_angle": -0.004368243991637956, "heading_rate": -0.008787734237170417, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059889.2293692}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.095, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059889.2293692}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059889.3296278, "x": -88.23529388718399, "y": 40.09278354450401, "z": 202.67876079608683, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": -0.096, "front_wheel_angle": -0.004414283547224972, "heading_rate": -0.008173374968998056, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059889.3293989}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.096, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059889.3293989}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059889.4295683, "x": -88.23529388718399, "y": 40.09278354450401, "z": 202.67876079608683, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.919126816221562, "steering_wheel_angle": -0.103, "front_wheel_angle": -0.004736594384715439, "heading_rate": -0.0074564914545869375, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059889.4294395}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.103, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059889.4294395}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059889.5294986, "x": -88.23529388718399, "y": 40.09278354450401, "z": 202.67876079608683, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8551218162215615, "steering_wheel_angle": -0.115, "front_wheel_angle": -0.005289265540233417, "heading_rate": -0.007272807940105653, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059889.5293722}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.115, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059889.5293722}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059889.6294942, "x": -88.2352669346332, "y": 40.09278497648054, "z": 202.67392390177736, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7704468162215616, "steering_wheel_angle": -0.118, "front_wheel_angle": -0.005427460639263251, "heading_rate": -0.005872739685016052, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059889.6293693}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.118, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059889.6293693}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059889.729485, "x": -88.2352669346332, "y": 40.09278497648054, "z": 202.67392390177736, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.716446816221562, "steering_wheel_angle": -0.118, "front_wheel_angle": -0.005427460639263251, "heading_rate": -0.004727873464832417, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059889.729394}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.118, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059889.729394}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059889.829528, "x": -88.2352669346332, "y": 40.09278497648054, "z": 202.67392390177736, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.662461816221562, "steering_wheel_angle": -0.118, "front_wheel_angle": -0.005427460639263251, "heading_rate": -0.003434598660550904, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059889.8293736}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.118, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059889.8293736}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059889.9294922, "x": -88.2352669346332, "y": 40.09278497648054, "z": 202.67392390177736, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6201668162215617, "steering_wheel_angle": -0.118, "front_wheel_angle": -0.005427460639263251, "heading_rate": -0.0022685312140675725, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059889.9293911}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.118, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059889.9293911}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059890.0294712, "x": -88.2352669346332, "y": 40.09278497648054, "z": 202.67392390177736, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5888178162215616, "steering_wheel_angle": -0.118, "front_wheel_angle": -0.005427460639263251, "heading_rate": -0.0012720735779818161, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059890.0293636}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.118, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059890.0293636}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059890.1295302, "x": -88.2352576542051, "y": 40.09278538724865, "z": 202.6733312261027, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5629428162215615, "steering_wheel_angle": -0.118, "front_wheel_angle": -0.005427460639263251, "heading_rate": -0.00031801839449545403, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059890.1294048}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.118, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059890.1294048}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059890.2295015, "x": -88.2352576542051, "y": 40.09278538724865, "z": 202.6733312261027, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5577428162215616, "steering_wheel_angle": -0.119, "front_wheel_angle": -0.005473528100865687, "heading_rate": -0.00010690591333842062, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059890.22937}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.119, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059890.22937}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059890.3294997, "x": -88.2352576542051, "y": 40.09278538724865, "z": 202.6733312261027, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5582538162215616, "steering_wheel_angle": -0.118, "front_wheel_angle": -0.005427460639263251, "heading_rate": -0.00012720735779818163, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059890.3293712}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.118, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059890.3293712}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059890.4296691, "x": -88.2352576542051, "y": 40.09278538724865, "z": 202.6733312261027, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5567268162215617, "steering_wheel_angle": -0.119, "front_wheel_angle": -0.005473528100865687, "heading_rate": -6.414354800305237e-05, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059890.4294481}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.119, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059890.4294481}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059890.52953, "x": -88.2352576542051, "y": 40.09278538724865, "z": 202.6733312261027, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5557188162215616, "steering_wheel_angle": -0.133, "front_wheel_angle": -0.006118600124947055, "heading_rate": -2.390108000252729e-05, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059890.5294006}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.133, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059890.5294006}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059890.6294818, "x": -88.23525644897244, "y": 40.09278544954769, "z": 202.676401275777, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.153, "front_wheel_angle": -0.007040545026252959, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059890.6293895}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.153, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059890.6293895}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059890.7294748, "x": -88.23525644897244, "y": 40.09278544954769, "z": 202.676401275777, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.181, "front_wheel_angle": -0.008332086375539805, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059890.7293622}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.181, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059890.7293622}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059890.8294704, "x": -88.23525644897244, "y": 40.09278544954769, "z": 202.676401275777, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.262, "front_wheel_angle": -0.012073726183044352, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059890.8293626}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.262, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059890.8293626}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059890.9299097, "x": -88.23525644897244, "y": 40.09278544954769, "z": 202.676401275777, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.41, "front_wheel_angle": -0.018931155110258103, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059890.929407}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.41, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059890.929407}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059891.0295215, "x": -88.23525644897244, "y": 40.09278544954769, "z": 202.676401275777, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.653, "front_wheel_angle": -0.0302495129438494, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059891.0293717}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.653, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059891.0293717}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059891.1294959, "x": -88.23525572942003, "y": 40.0927855180996, "z": 202.68094444452595, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -1.101, "front_wheel_angle": -0.051313604365133283, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059891.1293669}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.101, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059891.1293669}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059891.2295377, "x": -88.23525572942003, "y": 40.0927855180996, "z": 202.68094444452595, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -1.675, "front_wheel_angle": -0.07868921296825407, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059891.2293937}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.675, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059891.2293937}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059891.3294988, "x": -88.23525572942003, "y": 40.0927855180996, "z": 202.68094444452595, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -2.217, "front_wheel_angle": -0.10495602357981365, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059891.3293686}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.217, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059891.3293686}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059891.4294853, "x": -88.23525572942003, "y": 40.0927855180996, "z": 202.68094444452595, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5557188162215616, "steering_wheel_angle": -2.681, "front_wheel_angle": -0.1277799889050045, "heading_rate": -0.000501875052269173, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059891.4293928}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.681, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059891.4293928}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059891.5294886, "x": -88.23525572942003, "y": 40.0927855180996, "z": 202.68094444452595, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5661588162215616, "steering_wheel_angle": -3.054, "front_wheel_angle": -0.1463627777720231, "heading_rate": -0.01209279606576157, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059891.5293899}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.21, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.054, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059891.5293899}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059891.6295576, "x": -88.23525564602784, "y": 40.092785447339914, "z": 202.6932104688761, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.559281816221562, "steering_wheel_angle": -3.293, "front_wheel_angle": -0.15838354250685036, "heading_rate": -0.004991291762647988, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059891.6293988}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.293, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059891.6293988}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059891.7295322, "x": -88.23525564602784, "y": 40.092785447339914, "z": 202.6932104688761, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5650788162215616, "steering_wheel_angle": -3.577, "front_wheel_angle": -0.17278651766396239, "heading_rate": -0.012953162998300986, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059891.7294}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.19, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.577, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059891.7294}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059891.829542, "x": -88.23525564602784, "y": 40.092785447339914, "z": 202.6932104688761, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5582538162215616, "steering_wheel_angle": -3.863, "front_wheel_angle": -0.18742482589304008, "heading_rate": -0.004444939023831281, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059891.8294055}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.863, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059891.8294055}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059891.929624, "x": -88.23525564602784, "y": 40.092785447339914, "z": 202.6932104688761, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5688938162215615, "steering_wheel_angle": -4.167, "front_wheel_angle": -0.20313600449779237, "heading_rate": -0.020919538067484162, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059891.929452}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.26, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.167, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059891.929452}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059892.0295768, "x": -88.23525564602784, "y": 40.092785447339914, "z": 202.6932104688761, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5650788162215616, "steering_wheel_angle": -4.462, "front_wheel_angle": -0.21853583565363527, "heading_rate": -0.016482688722591583, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059892.029401}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.19, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.462, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059892.029401}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059892.1295006, "x": -88.23525564602784, "y": 40.092785447339914, "z": 202.6932104688761, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5733738162215616, "steering_wheel_angle": -4.795, "front_wheel_angle": -0.23610721320634248, "heading_rate": -0.031953983246481237, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059892.1293683}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059892.1293683}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059892.2295146, "x": -88.23525488965358, "y": 40.09278542531235, "z": 202.70810112854124, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5768178162215616, "steering_wheel_angle": -5.235, "front_wheel_angle": -0.25964169470255144, "heading_rate": -0.041505924472238095, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059892.2293932}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.235, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059892.2293932}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059892.3303921, "x": -88.23525488965358, "y": 40.09278542531235, "z": 202.70810112854124, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5815218162215614, "steering_wheel_angle": -5.64, "front_wheel_angle": -0.2816367926574113, "heading_rate": -0.0542488681384147, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059892.3295252}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.64, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059892.3295252}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059892.4295251, "x": -88.23525488965358, "y": 40.09278542531235, "z": 202.70810112854124, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5906868162215617, "steering_wheel_angle": -5.978, "front_wheel_angle": -0.3002481099040346, "heading_rate": -0.0761926237126166, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059892.429365}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.63, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.978, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059892.429365}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059892.529987, "x": -88.23525488965358, "y": 40.09278542531235, "z": 202.70810112854124, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5957588162215615, "steering_wheel_angle": -6.272, "front_wheel_angle": -0.31663274734459373, "heading_rate": -0.0908734867973968, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059892.5294242}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.71, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.272, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059892.5294242}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059892.6295028, "x": -88.23525182510676, "y": 40.09278524746491, "z": 202.71171451047974, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6049428162215618, "steering_wheel_angle": -6.504, "front_wheel_angle": -0.32969526201410637, "heading_rate": -0.11361591811624176, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059892.6293728}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.504, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059892.6293728}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059892.7295244, "x": -88.23525182510676, "y": 40.09278524746491, "z": 202.71171451047974, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.614518816221562, "steering_wheel_angle": -6.7, "front_wheel_angle": -0.3408249915080709, "heading_rate": -0.13715574922180304, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059892.7293715}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.7, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059892.7293715}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059892.8295696, "x": -88.23525182510676, "y": 40.09278524746491, "z": 202.71171451047974, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6311018162215616, "steering_wheel_angle": -6.91, "front_wheel_angle": -0.35284787399878326, "heading_rate": -0.17549852658126217, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059892.8293748}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.91, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059892.8293748}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059892.9295273, "x": -88.23525182510676, "y": 40.09278524746491, "z": 202.71171451047974, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6333428162215617, "steering_wheel_angle": -7.083, "front_wheel_angle": -0.36283055162679884, "heading_rate": -0.18537006280889418, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059892.929393}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.25, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.083, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059892.929393}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059893.0294797, "x": -88.23525182510676, "y": 40.09278524746491, "z": 202.71171451047974, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6535188162215615, "steering_wheel_angle": -7.134, "front_wheel_angle": -0.3657871323689622, "heading_rate": -0.22592454687068814, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059893.0293806}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.51, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.134, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059893.0293806}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059893.1294498, "x": -88.23524488020675, "y": 40.09278445437072, "z": 202.72552420788483, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6682788162215614, "steering_wheel_angle": -7.044, "front_wheel_angle": -0.3605738728890381, "heading_rate": -0.24891730882988441, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059893.1293569}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.044, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059893.1293569}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059893.229489, "x": -88.23524488020675, "y": 40.09278445437072, "z": 202.72552420788483, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6759018162215615, "steering_wheel_angle": -6.667, "front_wheel_angle": -0.3389449755189879, "heading_rate": -0.24513261724189964, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059893.2293637}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.78, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.667, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059893.2293637}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059893.3300111, "x": -88.23524488020675, "y": 40.09278445437072, "z": 202.72552420788483, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6943188162215614, "steering_wheel_angle": -5.987, "front_wheel_angle": -0.3007469375925315, "heading_rate": -0.24109693429168522, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059893.3295393}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.987, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059893.3295393}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059893.429671, "x": -88.23524488020675, "y": 40.09278445437072, "z": 202.72552420788483, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6907428162215616, "steering_wheel_angle": -5.262, "front_wheel_angle": -0.2610979458679486, "heading_rate": -0.2035293688497135, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059893.4294412}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.262, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059893.4294412}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059893.5296307, "x": -88.23524488020675, "y": 40.09278445437072, "z": 202.72552420788483, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7279428162215615, "steering_wheel_angle": -4.53, "front_wheel_angle": -0.2221075973469096, "heading_rate": -0.2073080565833577, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059893.5294387}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.35, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.53, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059893.5294387}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059893.6298563, "x": -88.23523352183115, "y": 40.09278263505214, "z": 202.7143426941722, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7240788162215614, "steering_wheel_angle": -3.76, "front_wheel_angle": -0.18213727030238963, "heading_rate": -0.1661922579264653, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059893.6294117}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.76, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059893.6294117}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059893.7295132, "x": -88.23523352183115, "y": 40.09278263505214, "z": 202.7143426941722, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7387338162215618, "steering_wheel_angle": -2.99, "front_wheel_angle": -0.14315906461183406, "heading_rate": -0.13851447149156734, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059893.7293682}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.99, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059893.7293682}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059893.8295367, "x": -88.23523352183115, "y": 40.09278263505214, "z": 202.7143426941722, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7558868162215617, "steering_wheel_angle": -2.193, "front_wheel_angle": -0.10378406526148166, "heading_rate": -0.10700638024844304, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059893.8293993}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.63, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.193, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059893.8293993}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059893.9295073, "x": -88.23523352183115, "y": 40.09278263505214, "z": 202.7143426941722, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7507818162215614, "steering_wheel_angle": -1.392, "front_wheel_angle": -0.06513668763984622, "heading_rate": -0.06573856592113948, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059893.9293659}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.58, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.392, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059893.9293659}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059894.0296245, "x": -88.23523352183115, "y": 40.09278263505214, "z": 202.7143426941722, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7768068162215616, "steering_wheel_angle": -0.621, "front_wheel_angle": -0.028754781808399785, "heading_rate": -0.031796276636404885, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059894.0294027}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.621, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059894.0294027}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059894.1295152, "x": -88.23521858591015, "y": 40.09278014490476, "z": 202.7137233378591, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7778738162215615, "steering_wheel_angle": 0.111, "front_wheel_angle": 0.005105022404758634, "heading_rate": 0.005663433429089824, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059894.129371}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.84, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.111, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059894.129371}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059894.2295604, "x": -88.23521858591015, "y": 40.09278014490476, "z": 202.7137233378591, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7768068162215616, "steering_wheel_angle": 0.825, "front_wheel_angle": 0.038306016753113944, "heading_rate": 0.042366828820031406, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059894.2293947}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.825, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059894.2293947}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059894.3295448, "x": -88.23521858591015, "y": 40.09278014490476, "z": 202.7137233378591, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7952178162215615, "steering_wheel_angle": 1.552, "front_wheel_angle": 0.0727854618578966, "heading_rate": 0.08544640691145503, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059894.3293962}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.552, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059894.3293962}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059894.4295528, "x": -88.23521858591015, "y": 40.09278014490476, "z": 202.7137233378591, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7843178162215616, "steering_wheel_angle": 2.244, "front_wheel_angle": 0.10627547367778425, "heading_rate": 0.12084549014015872, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059894.4294066}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.9, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.244, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059894.4294066}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059894.529486, "x": -88.23521858591015, "y": 40.09278014490476, "z": 202.7137233378591, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8007428162215615, "steering_wheel_angle": 2.929, "front_wheel_angle": 0.14011144872997486, "heading_rate": 0.16803064619365463, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059894.5293932}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.929, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059894.5293932}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059894.629515, "x": -88.23520196370892, "y": 40.09277827028389, "z": 202.73498712339287, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7930218162215614, "steering_wheel_angle": 3.587, "front_wheel_angle": 0.1732960580767805, "heading_rate": 0.2037713934653645, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059894.6293986}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.587, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059894.6293986}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059894.7294922, "x": -88.23520196370892, "y": 40.09277827028389, "z": 202.73498712339287, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8119428162215616, "steering_wheel_angle": 4.241, "front_wheel_angle": 0.2069845992567663, "heading_rate": 0.2583886800202831, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059894.7293696}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.241, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059894.7293696}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059894.8300357, "x": -88.23520196370892, "y": 40.09277827028389, "z": 202.73498712339287, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7941188162215616, "steering_wheel_angle": 4.908, "front_wheel_angle": 0.2421163110505834, "heading_rate": 0.28844263393646613, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059894.8294396}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.908, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059894.8294396}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059894.9295204, "x": -88.23520196370892, "y": 40.09277827028389, "z": 202.73498712339287, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8153418162215615, "steering_wheel_angle": 5.576, "front_wheel_angle": 0.27813920156552796, "heading_rate": 0.3546951350657873, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059894.929366}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.18, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.576, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059894.929366}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059895.0295382, "x": -88.23520196370892, "y": 40.09277827028389, "z": 202.73498712339287, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7941188162215616, "steering_wheel_angle": 6.211, "front_wheel_angle": 0.31321788354778457, "heading_rate": 0.37828084048157523, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059895.029367}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.211, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059895.029367}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059895.1295164, "x": -88.23518536655705, "y": 40.09277813572371, "z": 202.72844403893723, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8074388162215618, "steering_wheel_angle": 6.793, "front_wheel_angle": 0.3461367351209101, "heading_rate": 0.43814142808623896, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059895.129365}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.11, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.793, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059895.129365}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059895.229655, "x": -88.23518536655705, "y": 40.09277813572371, "z": 202.72844403893723, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8040818162215615, "steering_wheel_angle": 7.395, "front_wheel_angle": 0.38101760400725326, "heading_rate": 0.48196362702747986, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059895.229378}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.395, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059895.229378}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059895.329566, "x": -88.23518536655705, "y": 40.09277813572371, "z": 202.72844403893723, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8108138162215615, "steering_wheel_angle": 8.01, "front_wheel_angle": 0.4175922123568711, "heading_rate": 0.5442106664025659, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059895.3293962}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.14, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.01, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059895.3293962}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059895.4294732, "x": -88.23518536655705, "y": 40.09277813572371, "z": 202.72844403893723, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.801853816221562, "steering_wheel_angle": 8.611, "front_wheel_angle": 0.4543290133611627, "heading_rate": 0.5837971302928968, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059895.4293575}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.611, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059895.4293575}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059895.5294573, "x": -88.23518536655705, "y": 40.09277813572371, "z": 202.72844403893723, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8063178162215614, "steering_wheel_angle": 9.152, "front_wheel_angle": 0.4883105821016802, "heading_rate": 0.6432742624376009, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059895.5293543}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059895.5293543}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059895.6299403, "x": -88.23517045353778, "y": 40.09278109954485, "z": 202.7258714273663, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7974218162215614, "steering_wheel_angle": 9.586, "front_wheel_angle": 0.516245993199782, "heading_rate": 0.6695762637700651, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059895.6294334}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.586, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059895.6294334}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059895.729513, "x": -88.23517045353778, "y": 40.09278109954485, "z": 202.7258714273663, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8051988162215613, "steering_wheel_angle": 9.931, "front_wheel_angle": 0.538911207267707, "heading_rate": 0.7217450295487512, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059895.7293634}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.09, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.931, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059895.7293634}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059895.829496, "x": -88.23517045353778, "y": 40.09278109954485, "z": 202.7258714273663, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7974218162215614, "steering_wheel_angle": 10.188, "front_wheel_angle": 0.5560740641006101, "heading_rate": 0.7331685246772222, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059895.8293626}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.188, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059895.8293626}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059895.9295015, "x": -88.23517045353778, "y": 40.09278109954485, "z": 202.7258714273663, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8040818162215615, "steering_wheel_angle": 10.449, "front_wheel_angle": 0.5737596773398578, "heading_rate": 0.7775624779457659, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059895.9293635}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.449, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059895.9293635}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059896.029588, "x": -88.23517045353778, "y": 40.09278109954485, "z": 202.7258714273663, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7974218162215614, "steering_wheel_angle": 10.739, "front_wheel_angle": 0.5937267629769267, "heading_rate": 0.7962497332143983, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059896.0293727}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.739, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059896.0293727}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059896.1295195, "x": -88.23515878311787, "y": 40.09278743981008, "z": 202.7283208262452, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7963188162215618, "steering_wheel_angle": 10.991, "front_wheel_angle": 0.6113610215629693, "heading_rate": 0.8241599355427922, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059896.129391}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.991, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059896.129391}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059896.2294712, "x": -88.23515878311787, "y": 40.09278743981008, "z": 202.7283208262452, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.801853816221562, "steering_wheel_angle": 11.027, "front_wheel_angle": 0.6139024868353804, "heading_rate": 0.8423888129382131, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059896.2293816}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.027, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059896.2293816}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059896.3294792, "x": -88.23515878311787, "y": 40.09278743981008, "z": 202.7283208262452, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7919268162215616, "steering_wheel_angle": 11.033, "front_wheel_angle": 0.6143266158780261, "heading_rate": 0.8183493338182561, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059896.3293834}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.033, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059896.3293834}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059896.429481, "x": -88.23515878311787, "y": 40.09278743981008, "z": 202.7283208262452, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.789742816221562, "steering_wheel_angle": 11.028, "front_wheel_angle": 0.6139731640416383, "heading_rate": 0.8122287631356486, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059896.429361}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.028, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059896.429361}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059896.529541, "x": -88.23515878311787, "y": 40.09278743981008, "z": 202.7283208262452, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7963188162215618, "steering_wheel_angle": 11.028, "front_wheel_angle": 0.6139731640416383, "heading_rate": 0.8287486701824753, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059896.5293844}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.028, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059896.5293844}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059896.6295276, "x": -88.23515051979909, "y": 40.09279601448499, "z": 202.723464538256, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.789742816221562, "steering_wheel_angle": 11.027, "front_wheel_angle": 0.6139024868353804, "heading_rate": 0.8121068621463166, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059896.629367}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.027, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059896.629367}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059896.7295885, "x": -88.23515051979909, "y": 40.09279601448499, "z": 202.723464538256, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7996338162215615, "steering_wheel_angle": 11.027, "front_wheel_angle": 0.6139024868353804, "heading_rate": 0.8368830037033228, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059896.7293782}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.04, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.027, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059896.7293782}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059896.8297248, "x": -88.23515051979909, "y": 40.09279601448499, "z": 202.723464538256, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7886538162215615, "steering_wheel_angle": 11.027, "front_wheel_angle": 0.6139024868353804, "heading_rate": 0.8093539575288713, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059896.829398}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.94, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.027, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059896.829398}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059896.9296014, "x": -88.23515051979909, "y": 40.09279601448499, "z": 202.723464538256, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7985268162215613, "steering_wheel_angle": 11.027, "front_wheel_angle": 0.6139024868353804, "heading_rate": 0.8341300990858777, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059896.9293828}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.027, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059896.9293828}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059897.02946, "x": -88.23515051979909, "y": 40.09279601448499, "z": 202.723464538256, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7908338162215616, "steering_wheel_angle": 11.025, "front_wheel_angle": 0.6137611455773521, "heading_rate": 0.8146151976466994, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059897.0293522}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.96, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059897.0293522}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059897.129546, "x": -88.23514584956962, "y": 40.09280574061108, "z": 202.70949794640342, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8007428162215615, "steering_wheel_angle": 11.025, "front_wheel_angle": 0.6137611455773521, "heading_rate": 0.8393839029805518, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059897.1293693}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059897.1293693}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059897.22951, "x": -88.23514584956962, "y": 40.09280574061108, "z": 202.70949794640342, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7930218162215614, "steering_wheel_angle": 11.025, "front_wheel_angle": 0.6137611455773521, "heading_rate": 0.8201193543875555, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059897.2293644}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059897.2293644}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059897.3295135, "x": -88.23514584956962, "y": 40.09280574061108, "z": 202.70949794640342, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8051988162215613, "steering_wheel_angle": 11.024, "front_wheel_angle": 0.6136904815239496, "heading_rate": 0.8502645922409794, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059897.3293648}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.09, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.024, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059897.3293648}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059897.4296327, "x": -88.23514584956962, "y": 40.09280574061108, "z": 202.70949794640342, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.801853816221562, "steering_wheel_angle": 11.024, "front_wheel_angle": 0.6136904815239496, "heading_rate": 0.842009596199805, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059897.4294133}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.024, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059897.4294133}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059897.5295172, "x": -88.23514584956962, "y": 40.09280574061108, "z": 202.70949794640342, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7996338162215615, "steering_wheel_angle": 11.023, "front_wheel_angle": 0.6136198218532006, "heading_rate": 0.8363807266868332, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059897.5293674}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.04, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.023, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059897.5293674}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059897.6295907, "x": -88.23514519652808, "y": 40.092815865518176, "z": 202.7082405426272, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.801853816221562, "steering_wheel_angle": 11.023, "front_wheel_angle": 0.6136198218532006, "heading_rate": 0.8418832314676676, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059897.6294231}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.023, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059897.6294231}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059897.7294822, "x": -88.23514519652808, "y": 40.092815865518176, "z": 202.7082405426272, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8051988162215613, "steering_wheel_angle": 11.022, "front_wheel_angle": 0.6135491665642899, "heading_rate": 0.8500094056490768, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059897.7293572}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.09, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.022, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059897.7293572}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059897.829505, "x": -88.23514519652808, "y": 40.092815865518176, "z": 202.7082405426272, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8142068162215614, "steering_wheel_angle": 11.022, "front_wheel_angle": 0.6135491665642899, "heading_rate": 0.8720161216529364, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059897.8293598}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.17, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.022, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059897.8293598}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059897.9295077, "x": -88.23514519652808, "y": 40.092815865518176, "z": 202.7082405426272, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8074388162215618, "steering_wheel_angle": 11.015, "front_wheel_angle": 0.6130547021649491, "heading_rate": 0.8546128035480466, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059897.929363}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.11, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059897.929363}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059898.029497, "x": -88.23514519652808, "y": 40.092815865518176, "z": 202.7082405426272, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8199018162215617, "steering_wheel_angle": 11.012, "front_wheel_angle": 0.6128428544970891, "heading_rate": 0.8844419933284874, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059898.0293584}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.012, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059898.0293584}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059898.129515, "x": -88.23514911642081, "y": 40.09282609337837, "z": 202.70136136622847, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8199018162215617, "steering_wheel_angle": 11.012, "front_wheel_angle": 0.6128428544970891, "heading_rate": 0.8844419933284874, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059898.129368}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.012, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059898.129368}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059898.2295194, "x": -88.23514911642081, "y": 40.09282609337837, "z": 202.70136136622847, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.824493816221562, "steering_wheel_angle": 11.012, "front_wheel_angle": 0.6128428544970891, "heading_rate": 0.8954288503884685, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059898.229367}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.26, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.012, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059898.229367}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059898.329539, "x": -88.23514911642081, "y": 40.09282609337837, "z": 202.70136136622847, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8314418162215613, "steering_wheel_angle": 11.011, "front_wheel_angle": 0.6127722473546579, "heading_rate": 0.911772299635319, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059898.329386}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.32, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.011, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059898.329386}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059898.4295528, "x": -88.23514911642081, "y": 40.09282609337837, "z": 202.70136136622847, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8337738162215613, "steering_wheel_angle": 11.004, "front_wheel_angle": 0.6122781197302468, "heading_rate": 0.9163019001190719, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059898.4293714}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.004, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059898.4293714}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059898.5295153, "x": -88.23514911642081, "y": 40.09282609337837, "z": 202.70136136622847, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8443668162215614, "steering_wheel_angle": 11.004, "front_wheel_angle": 0.6122781197302468, "heading_rate": 0.9409926698827595, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059898.5293665}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 11.004, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059898.5293665}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059898.6294575, "x": -88.23515758105539, "y": 40.09283572110454, "z": 202.72119326463368, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8503218162215616, "steering_wheel_angle": 10.997, "front_wheel_angle": 0.6117842060592159, "heading_rate": 0.953707525201804, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059898.6293511}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.997, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059898.6293511}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059898.7294579, "x": -88.23515758105539, "y": 40.09283572110454, "z": 202.72119326463368, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8551218162215615, "steering_wheel_angle": 10.894, "front_wheel_angle": 0.6045411772705841, "heading_rate": 0.9498833783052241, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059898.7293503}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.894, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059898.7293503}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059898.8294957, "x": -88.23515758105539, "y": 40.09283572110454, "z": 202.72119326463368, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.858742816221562, "steering_wheel_angle": 10.647, "front_wheel_angle": 0.5873553342336437, "heading_rate": 0.923183220545241, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059898.8293617}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.55, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.647, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059898.8293617}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059898.929506, "x": -88.23515758105539, "y": 40.09283572110454, "z": 202.72119326463368, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8599538162215614, "steering_wheel_angle": 10.352, "front_wheel_angle": 0.5671560646016215, "heading_rate": 0.8857773697573019, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059898.929362}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.352, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059898.929362}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059899.0295088, "x": -88.23515758105539, "y": 40.09283572110454, "z": 202.72119326463368, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8783588162215614, "steering_wheel_angle": 10.109, "front_wheel_angle": 0.5507722391959029, "heading_rate": 0.8900641278610203, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059899.0293653}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.71, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.109, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059899.0293653}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059899.129507, "x": -88.23517086021046, "y": 40.09284330173573, "z": 202.74800613077275, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.874641816221562, "steering_wheel_angle": 9.809, "front_wheel_angle": 0.5308482214861103, "heading_rate": 0.843894429287175, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059899.1293604}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.68, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.809, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059899.1293604}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059899.2299206, "x": -88.23517086021046, "y": 40.09284330173573, "z": 202.74800613077275, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8959428162215617, "steering_wheel_angle": 9.494, "front_wheel_angle": 0.5102717497654037, "heading_rate": 0.841759706823326, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059899.2295332}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.494, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059899.2295332}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059899.329509, "x": -88.23517086021046, "y": 40.09284330173573, "z": 202.74800613077275, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8972138162215613, "steering_wheel_angle": 9.494, "front_wheel_angle": 0.5102717497654037, "heading_rate": 0.8439460956722178, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059899.3293626}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.86, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.494, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059899.3293626}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059899.429473, "x": -88.23517086021046, "y": 40.09284330173573, "z": 202.74800613077275, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9178218162215614, "steering_wheel_angle": 9.08, "front_wheel_angle": 0.48373559661442705, "heading_rate": 0.8249922434807738, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059899.4293547}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.08, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059899.4293547}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059899.529466, "x": -88.23517086021046, "y": 40.09284330173573, "z": 202.74800613077275, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9230538162215614, "steering_wheel_angle": 8.531, "front_wheel_angle": 0.4493791899102173, "heading_rate": 0.7648812002190295, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059899.5293531}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.531, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059899.5293531}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059899.6294768, "x": -88.23518876147308, "y": 40.09284812935379, "z": 202.76835979838125, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9283178162215613, "steering_wheel_angle": 7.826, "front_wheel_angle": 0.40654540393363275, "heading_rate": 0.6895209623170387, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059899.6293554}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.826, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059899.6293554}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059899.729631, "x": -88.23518876147308, "y": 40.09284812935379, "z": 202.76835979838125, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9456468162215614, "steering_wheel_angle": 7.038, "front_wheel_angle": 0.36022701608666463, "heading_rate": 0.6223751896624439, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059899.7293909}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.038, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059899.7293909}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059899.829521, "x": -88.23518876147308, "y": 40.09284812935379, "z": 202.76835979838125, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9551178162215614, "steering_wheel_angle": 6.345, "front_wheel_angle": 0.3207300896323998, "heading_rate": 0.5579919670500806, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059899.8293643}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.345, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059899.8293643}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059899.9295194, "x": -88.23518876147308, "y": 40.09284812935379, "z": 202.76835979838125, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.968817816221562, "steering_wheel_angle": 5.703, "front_wheel_angle": 0.2850878733916268, "heading_rate": 0.5037158179695586, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059899.9293635}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.703, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059899.9293635}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059900.0296323, "x": -88.23518876147308, "y": 40.09284812935379, "z": 202.76835979838125, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9996618162215616, "steering_wheel_angle": 5.051, "front_wheel_angle": 0.2497551779800374, "heading_rate": 0.460341768710467, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059900.0293803}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059900.0293803}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059900.1294656, "x": -88.23521131829195, "y": 40.09285102543354, "z": 202.77707370564644, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.032942816221562, "steering_wheel_angle": 4.504, "front_wheel_angle": 0.22074094062097238, "heading_rate": 0.42512815654180164, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059900.1293552}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.504, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059900.1293552}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059900.22944, "x": -88.23521131829195, "y": 40.09285102543354, "z": 202.77707370564644, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": 4.008, "front_wheel_angle": 0.19489888317754206, "heading_rate": 0.38478503374307194, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059900.2293508}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.008, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059900.2293508}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059900.329522, "x": -88.23521131829195, "y": 40.09285102543354, "z": 202.77707370564644, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": 3.568, "front_wheel_angle": 0.1723280717314832, "heading_rate": 0.35014861167065947, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059900.329378}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.568, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059900.329378}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059900.4296155, "x": -88.23521131829195, "y": 40.09285102543354, "z": 202.77707370564644, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": 3.125, "front_wheel_angle": 0.1499243884178445, "heading_rate": 0.31332708755197203, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059900.4293768}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.125, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059900.4293768}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059900.529521, "x": -88.23521131829195, "y": 40.09285102543354, "z": 202.77707370564644, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": 2.595, "front_wheel_angle": 0.1235255488231461, "heading_rate": 0.2657750365884468, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059900.529368}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.595, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059900.529368}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059900.6295228, "x": -88.2352401063671, "y": 40.0928516234943, "z": 202.75969421306945, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": 2.0, "front_wheel_angle": 0.094389672668791, "heading_rate": 0.21153050232723034, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059900.629366}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.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": 1744059900.629366}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059900.7295175, "x": -88.2352401063671, "y": 40.0928516234943, "z": 202.75969421306945, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1966388162215615, "steering_wheel_angle": 1.456, "front_wheel_angle": 0.06819203035154317, "heading_rate": 0.1571385932095057, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059900.7293608}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059900.7293608}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059900.8294985, "x": -88.2352401063671, "y": 40.0928516234943, "z": 202.75969421306945, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.210126816221561, "steering_wheel_angle": 1.079, "front_wheel_angle": 0.05027312296073177, "heading_rate": 0.11733736274358579, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059900.8293583}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.079, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059900.8293583}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059900.9295037, "x": -88.2352401063671, "y": 40.0928516234943, "z": 202.75969421306945, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.2531018162215615, "steering_wheel_angle": 1.048, "front_wheel_angle": 0.04880806831915527, "heading_rate": 0.11868261145971568, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059900.9293606}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.048, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059900.9293606}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059901.0294883, "x": -88.2352401063671, "y": 40.0928516234943, "z": 202.75969421306945, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": 1.063, "front_wheel_angle": 0.04951680838841576, "heading_rate": 0.12350612955839364, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059901.029369}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.063, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059901.029369}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059901.1295743, "x": -88.23527466109715, "y": 40.09285064721308, "z": 202.80137498640792, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": 1.051, "front_wheel_angle": 0.04894979275063999, "heading_rate": 0.12362049337460007, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059901.1293807}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059901.1293807}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059901.229563, "x": -88.23527466109715, "y": 40.09285064721308, "z": 202.80137498640792, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.324461816221562, "steering_wheel_angle": 1.011, "front_wheel_angle": 0.0470611017656519, "heading_rate": 0.12178699026091123, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059901.2293675}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.011, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059901.2293675}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059901.3295758, "x": -88.23527466109715, "y": 40.09285064721308, "z": 202.80137498640792, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.340958816221562, "steering_wheel_angle": 0.872, "front_wheel_angle": 0.040514096914930235, "heading_rate": 0.10624938487131234, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059901.3293793}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.872, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059901.3293793}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059901.4295146, "x": -88.23527466109715, "y": 40.09285064721308, "z": 202.80137498640792, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": 0.701, "front_wheel_angle": 0.032494044522278956, "heading_rate": 0.08723151846240625, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059901.4293597}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.701, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059901.4293597}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059901.5295146, "x": -88.23527466109715, "y": 40.09285064721308, "z": 202.80137498640792, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.400926816221562, "steering_wheel_angle": 0.544, "front_wheel_angle": 0.025163384281178067, "heading_rate": 0.0691156008244467, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059901.5293624}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.544, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059901.5293624}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059901.6295114, "x": -88.2353132714179, "y": 40.09284838514004, "z": 202.8044754776463, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.400926816221562, "steering_wheel_angle": 0.398, "front_wheel_angle": 0.018374137433781756, "heading_rate": 0.05046278299169987, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059901.6293597}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.398, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059901.6293597}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059901.729466, "x": -88.2353132714179, "y": 40.09284838514004, "z": 202.8044754776463, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": 0.29, "front_wheel_angle": 0.013369004324805426, "heading_rate": 0.03760256492915296, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059901.7293518}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.29, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059901.7293518}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059901.8294556, "x": -88.2353132714179, "y": 40.09284838514004, "z": 202.8044754776463, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.449201816221562, "steering_wheel_angle": 0.198, "front_wheel_angle": 0.009116703161574537, "heading_rate": 0.02592634290278546, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059901.8293488}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.198, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059901.8293488}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059901.929462, "x": -88.2353132714179, "y": 40.09284838514004, "z": 202.8044754776463, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.480753816221561, "steering_wheel_angle": 0.16, "front_wheel_angle": 0.007363340777656139, "heading_rate": 0.021400095898877827, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059901.9293752}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.44, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.16, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059901.9293752}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059902.0295334, "x": -88.2353132714179, "y": 40.09284838514004, "z": 202.8044754776463, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.496721816221561, "steering_wheel_angle": 0.157, "front_wheel_angle": 0.007224992432841391, "heading_rate": 0.021223784570256327, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059902.0293612}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.52, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.157, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059902.0293612}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059902.1295176, "x": -88.2353132714179, "y": 40.09284838514004, "z": 202.8044754776463, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.514838816221562, "steering_wheel_angle": 0.173, "front_wheel_angle": 0.007962977019468269, "heading_rate": 0.023671693740477007, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059902.1293867}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.61, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.173, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059902.1293867}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059902.2295306, "x": -88.23535513514405, "y": 40.09284462109547, "z": 202.81537324333442, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.531078816221561, "steering_wheel_angle": 0.18, "front_wheel_angle": 0.008285943435522103, "heading_rate": 0.02489076691634033, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059902.229394}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.69, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059902.229394}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059902.330106, "x": -88.23535513514405, "y": 40.09284462109547, "z": 202.81537324333442, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.563942816221561, "steering_wheel_angle": 0.169, "front_wheel_angle": 0.007778451616404846, "heading_rate": 0.023852373710940993, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059902.3294768}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.85, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.169, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059902.3294768}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059902.4295523, "x": -88.23535513514405, "y": 40.09284462109547, "z": 202.81537324333442, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.580566816221562, "steering_wheel_angle": 0.145, "front_wheel_angle": 0.006671708657912529, "heading_rate": 0.020666966663853793, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059902.429412}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.145, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059902.429412}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059902.5295398, "x": -88.23535513514405, "y": 40.09284462109547, "z": 202.81537324333442, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.599421816221561, "steering_wheel_angle": 0.113, "front_wheel_angle": 0.005197141544735341, "heading_rate": 0.016281816588023083, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059902.529391}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.113, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059902.529391}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059902.6296575, "x": -88.23539984462435, "y": 40.09284008976451, "z": 202.82726907146267, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": 0.1, "front_wheel_angle": 0.004598453893036984, "heading_rate": 0.0145498980773878, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059902.629388}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059902.629388}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059902.7295864, "x": -88.23539984462435, "y": 40.09284008976451, "z": 202.82726907146267, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.616317816221562, "steering_wheel_angle": 0.1, "front_wheel_angle": 0.004598453893036984, "heading_rate": 0.0145498980773878, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059902.729404}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.1, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059902.729404}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059902.8294756, "x": -88.23539984462435, "y": 40.09284008976451, "z": 202.82726907146267, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.650493816221561, "steering_wheel_angle": 0.134, "front_wheel_angle": 0.006164685813487009, "heading_rate": 0.01989099604555358, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059902.8293521}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.26, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.134, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059902.8293521}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059902.9295015, "x": -88.23539984462435, "y": 40.09284008976451, "z": 202.82726907146267, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.667773816221562, "steering_wheel_angle": 0.185, "front_wheel_angle": 0.008516670340936358, "heading_rate": 0.02774638594742721, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059902.9293592}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.185, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059902.9293592}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059903.0297108, "x": -88.23539984462435, "y": 40.09284008976451, "z": 202.82726907146267, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.687366816221561, "steering_wheel_angle": 0.237, "front_wheel_angle": 0.01091804167070966, "heading_rate": 0.03595419866790997, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059903.0294}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.43, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.237, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059903.0294}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059903.1295993, "x": -88.23544693664495, "y": 40.09283504142282, "z": 202.8459680139313, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.704918816221562, "steering_wheel_angle": 0.26, "front_wheel_angle": 0.0119812431909017, "heading_rate": 0.039830179158318824, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059903.1293962}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.51, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.26, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059903.1293962}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059903.2295434, "x": -88.23544693664495, "y": 40.09283504142282, "z": 202.8459680139313, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.704918816221562, "steering_wheel_angle": 0.241, "front_wheel_angle": 0.011102899666132838, "heading_rate": 0.03690998394713344, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059903.2293973}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.51, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.241, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059903.2293973}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059903.3294668, "x": -88.23544693664495, "y": 40.09283504142282, "z": 202.8459680139313, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.722598816221561, "steering_wheel_angle": 0.208, "front_wheel_angle": 0.009578407398255724, "heading_rate": 0.032141029641399595, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059903.329351}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.59, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.208, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059903.329351}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059903.429548, "x": -88.23544693664495, "y": 40.09283504142282, "z": 202.8459680139313, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.740406816221562, "steering_wheel_angle": 0.183, "front_wheel_angle": 0.008424375916979102, "heading_rate": 0.028531666843449304, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059903.4293616}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.183, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059903.4293616}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059903.5294676, "x": -88.23544693664495, "y": 40.09283504142282, "z": 202.8459680139313, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.740406816221562, "steering_wheel_angle": 0.174, "front_wheel_angle": 0.008009111419146078, "heading_rate": 0.027125187806092996, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059903.5293748}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.174, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059903.5293748}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059903.6298313, "x": -88.23549615252581, "y": 40.09282935475787, "z": 202.83356380460074, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.758342816221561, "steering_wheel_angle": 0.171, "front_wheel_angle": 0.007870711879000536, "heading_rate": 0.026902402762599868, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059903.6294413}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.75, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.171, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059903.6294413}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059903.729585, "x": -88.23549615252581, "y": 40.09282935475787, "z": 202.83356380460074, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.776406816221561, "steering_wheel_angle": 0.17, "front_wheel_angle": 0.007824581138017272, "heading_rate": 0.02698924277148976, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059903.7293706}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.17, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059903.7293706}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059903.829517, "x": -88.23549615252581, "y": 40.09282935475787, "z": 202.83356380460074, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.796881816221561, "steering_wheel_angle": 0.163, "front_wheel_angle": 0.007501700088116369, "heading_rate": 0.02613922657908855, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059903.8293872}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059903.8293872}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059903.9302533, "x": -88.23549615252581, "y": 40.09282935475787, "z": 202.83356380460074, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.796881816221561, "steering_wheel_angle": 0.142, "front_wheel_angle": 0.006533415102241901, "heading_rate": 0.02276519216243045, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059903.9294543}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.92, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.142, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059903.9294543}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059904.029515, "x": -88.23549615252581, "y": 40.09282935475787, "z": 202.83356380460074, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.815217816221562, "steering_wheel_angle": 0.079, "front_wheel_angle": 0.003631775890244649, "heading_rate": 0.01276801825004322, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059904.0293858}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.079, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059904.0293858}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059904.1294825, "x": -88.23554718208175, "y": 40.092822616220204, "z": 202.84838692532296, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.833681816221562, "steering_wheel_angle": 0.082, "front_wheel_angle": 0.003769840040269683, "heading_rate": 0.01337121473542864, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059904.1293876}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.082, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059904.1293876}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059904.2294574, "x": -88.23554718208175, "y": 40.092822616220204, "z": 202.84838692532296, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.833681816221562, "steering_wheel_angle": 0.081, "front_wheel_angle": 0.0037238174461442725, "heading_rate": 0.013207976055208941, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059904.2293575}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.08, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.081, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059904.2293575}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059904.3294725, "x": -88.23554718208175, "y": 40.092822616220204, "z": 202.84838692532296, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.852273816221562, "steering_wheel_angle": 0.078, "front_wheel_angle": 0.0035857569282793833, "heading_rate": 0.012830341498405349, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059904.3293796}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.078, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059904.3293796}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059904.429491, "x": -88.23554718208175, "y": 40.092822616220204, "z": 202.84838692532296, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.870993816221562, "steering_wheel_angle": 0.067, "front_wheel_angle": 0.0030796282205738327, "heading_rate": 0.011115568249079806, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059904.4293811}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.067, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059904.4293811}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059904.5295131, "x": -88.23554718208175, "y": 40.092822616220204, "z": 202.84838692532296, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": 0.015, "front_wheel_angle": 0.0006889987791691868, "heading_rate": 0.002511077979246371, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059904.5293803}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059904.5293803}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059904.6294858, "x": -88.23559972812457, "y": 40.092815444690515, "z": 202.8366771773538, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": -0.018, "front_wheel_angle": -0.0008268310472349244, "heading_rate": -0.0030134122768239527, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059904.6293564}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.018, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059904.6293564}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059904.7294776, "x": -88.23559972812457, "y": 40.092815444690515, "z": 202.8366771773538, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.892206816221561, "steering_wheel_angle": -0.009, "front_wheel_angle": -0.00041336676293914716, "heading_rate": -0.0015065281710509323, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059904.7293537}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.009, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059904.7293537}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059904.8294182, "x": -88.23559972812457, "y": 40.092815444690515, "z": 202.8366771773538, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.930318816221561, "steering_wheel_angle": 0.007, "front_wheel_angle": 0.00032149905694411315, "heading_rate": 0.001191807091999737, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059904.8292928}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.49, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.007, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059904.8292928}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059904.9299686, "x": -88.23559972812457, "y": 40.092815444690515, "z": 202.8366771773538, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.930318816221561, "steering_wheel_angle": 0.044, "front_wheel_angle": 0.002021831861724432, "heading_rate": 0.007495004106363712, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059904.929441}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.49, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.044, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059904.929441}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059905.0294797, "x": -88.23559972812457, "y": 40.092815444690515, "z": 202.8366771773538, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.949566816221562, "steering_wheel_angle": 0.046, "front_wheel_angle": 0.0021137887840879614, "heading_rate": 0.00790194874692686, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059905.0293753}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.046, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059905.0293753}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059905.1295593, "x": -88.23565372998732, "y": 40.092808059599875, "z": 202.8393570290357, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.949566816221562, "steering_wheel_angle": 0.041, "front_wheel_angle": 0.0018839055326036736, "heading_rate": 0.007042577060909095, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059905.1293626}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059905.1293626}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059905.229589, "x": -88.23565372998732, "y": 40.092808059599875, "z": 202.8393570290357, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.968942816221562, "steering_wheel_angle": 0.039, "front_wheel_angle": 0.0017919606816966718, "heading_rate": 0.006754859018656365, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059905.2293983}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.039, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059905.2293983}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059905.3294945, "x": -88.23565372998732, "y": 40.092808059599875, "z": 202.8393570290357, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.968942816221562, "steering_wheel_angle": -0.015, "front_wheel_angle": -0.0006889987791691868, "heading_rate": -0.0025972028402708983, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059905.3293552}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059905.3293552}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059905.4294555, "x": -88.23565372998732, "y": 40.092808059599875, "z": 202.8393570290357, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.990893816221561, "steering_wheel_angle": -0.097, "front_wheel_angle": -0.0044603243150626555, "heading_rate": -0.016970252705805402, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059905.42935}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.097, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059905.42935}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059905.529508, "x": -88.23565372998732, "y": 40.092808059599875, "z": 202.8393570290357, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.010541816221561, "steering_wheel_angle": -0.152, "front_wheel_angle": -0.00699443621917048, "heading_rate": -0.026830657723614766, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059905.5293815}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059905.5293815}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059905.6294916, "x": -88.23570900284075, "y": 40.092800311752406, "z": 202.8622739514545, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.010541816221561, "steering_wheel_angle": -0.159, "front_wheel_angle": -0.007317223444441507, "heading_rate": -0.02806891276118736, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059905.6293826}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.159, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059905.6293826}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059905.729448, "x": -88.23570900284075, "y": 40.092800311752406, "z": 202.8622739514545, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.030317816221562, "steering_wheel_angle": -0.153, "front_wheel_angle": -0.007040545026252959, "heading_rate": -0.027227557603622804, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059905.7293503}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.9, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.153, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059905.7293503}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059905.8294344, "x": -88.23570900284075, "y": 40.092800311752406, "z": 202.8622739514545, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.030317816221562, "steering_wheel_angle": -0.161, "front_wheel_angle": -0.0074094593292757605, "heading_rate": -0.028654292876248714, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059905.829342}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.9, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059905.829342}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059905.9294314, "x": -88.23570900284075, "y": 40.092800311752406, "z": 202.8622739514545, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.050221816221562, "steering_wheel_angle": -0.169, "front_wheel_angle": -0.007778451616404846, "heading_rate": -0.03032441906180779, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059905.9293425}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.169, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059905.9293425}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059906.0295837, "x": -88.23570900284075, "y": 40.092800311752406, "z": 202.8622739514545, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.050221816221562, "steering_wheel_angle": -0.174, "front_wheel_angle": -0.008009111419146078, "heading_rate": -0.03122368792443, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059906.0294394}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.174, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059906.0294394}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059906.129498, "x": -88.23576563117255, "y": 40.092792772612846, "z": 202.84116379730963, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.090413816221561, "steering_wheel_angle": -0.177, "front_wheel_angle": -0.00814752193711561, "heading_rate": -0.03227253928241166, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059906.1293778}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.14, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.177, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059906.1293778}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059906.2295005, "x": -88.23576563117255, "y": 40.092792772612846, "z": 202.84116379730963, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.070253816221562, "steering_wheel_angle": -0.177, "front_wheel_angle": -0.00814752193711561, "heading_rate": -0.03201792358787587, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059906.2293785}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.177, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059906.2293785}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059906.3295572, "x": -88.23576563117255, "y": 40.092792772612846, "z": 202.84116379730963, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.113246816221562, "steering_wheel_angle": -0.18, "front_wheel_angle": -0.008285943435522103, "heading_rate": -0.03311216457141243, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059906.329422}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.18, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059906.329422}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059906.4295342, "x": -88.23576563117255, "y": 40.092792772612846, "z": 202.84116379730963, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.090413816221561, "steering_wheel_angle": -0.182, "front_wheel_angle": -0.00837823053599315, "heading_rate": -0.033186424021505886, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059906.42944}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.14, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.182, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059906.42944}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059906.5294943, "x": -88.23576563117255, "y": 40.092792772612846, "z": 202.84116379730963, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.113246816221562, "steering_wheel_angle": -0.186, "front_wheel_angle": -0.008562819384101573, "heading_rate": -0.034218665352852305, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059906.5293875}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.186, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059906.5293875}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059906.6294312, "x": -88.23582384794136, "y": 40.09278575826158, "z": 202.850504075786, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.133678816221561, "steering_wheel_angle": -0.205, "front_wheel_angle": -0.00943988328959379, "heading_rate": -0.03801878427610426, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059906.6293437}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.205, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059906.6293437}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059906.7294781, "x": -88.23582384794136, "y": 40.09278575826158, "z": 202.850504075786, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.113246816221562, "steering_wheel_angle": -0.212, "front_wheel_angle": -0.009763123333029217, "heading_rate": -0.03901559577650087, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059906.7293875}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.23, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.212, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059906.7293875}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059906.8294795, "x": -88.23582384794136, "y": 40.09278575826158, "z": 202.850504075786, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.154238816221562, "steering_wheel_angle": -0.201, "front_wheel_angle": -0.009255201596281284, "heading_rate": -0.03756417592664965, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059906.829378}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.39, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.201, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059906.829378}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059906.929487, "x": -88.23582384794136, "y": 40.09278575826158, "z": 202.850504075786, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.154238816221562, "steering_wheel_angle": -0.193, "front_wheel_angle": -0.008885896877447157, "heading_rate": -0.03606519476081598, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059906.9293683}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.39, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.193, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059906.9293683}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059907.0295608, "x": -88.23582384794136, "y": 40.09278575826158, "z": 202.850504075786, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.174926816221562, "steering_wheel_angle": -0.194, "front_wheel_angle": -0.00893205569068718, "heading_rate": -0.03653168366533042, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059907.029406}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.47, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.194, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059907.029406}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059907.1298046, "x": -88.23588326690557, "y": 40.09277952693092, "z": 202.87058828942378, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.154238816221562, "steering_wheel_angle": -0.195, "front_wheel_angle": -0.008978215725623, "heading_rate": -0.0364399093558419, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059907.129487}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.39, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.195, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059907.129487}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059907.2294316, "x": -88.23588326690557, "y": 40.09277952693092, "z": 202.87058828942378, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.174926816221562, "steering_wheel_angle": -0.2, "front_wheel_angle": -0.009209034229133432, "heading_rate": -0.03766457582282629, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059907.2293437}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.47, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059907.2293437}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059907.3294923, "x": -88.23588326690557, "y": 40.09277952693092, "z": 202.87058828942378, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.154238816221562, "steering_wheel_angle": -0.219, "front_wheel_angle": -0.010086423325216781, "heading_rate": -0.04093808296838447, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059907.329343}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.39, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.219, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059907.329343}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059907.4294503, "x": -88.23588326690557, "y": 40.09277952693092, "z": 202.87058828942378, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.174926816221562, "steering_wheel_angle": -0.22, "front_wheel_angle": -0.010132613934107136, "heading_rate": -0.041442226068532595, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059907.429353}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.47, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.22, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059907.429353}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059907.5295167, "x": -88.23588326690557, "y": 40.09277952693092, "z": 202.87058828942378, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.154238816221562, "steering_wheel_angle": -0.209, "front_wheel_angle": -0.009624584547123486, "heading_rate": -0.03906348488116811, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059907.529381}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.39, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.209, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059907.529381}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059907.6296222, "x": -88.23594367993314, "y": 40.0927744073998, "z": 202.85280040234113, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.133678816221561, "steering_wheel_angle": -0.2, "front_wheel_angle": -0.009209034229133432, "heading_rate": -0.03708899491244882, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059907.6293678}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059907.6293678}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059907.729656, "x": -88.23594367993314, "y": 40.0927744073998, "z": 202.85280040234113, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -5.070253816221562, "steering_wheel_angle": -0.199, "front_wheel_angle": -0.00916286808426341, "heading_rate": -0.036008215908268554, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059907.7293847}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 10.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.199, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059907.7293847}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059907.8294787, "x": -88.23594367993314, "y": 40.0927744073998, "z": 202.85280040234113, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.968942816221562, "steering_wheel_angle": -0.201, "front_wheel_angle": -0.009255201596281284, "heading_rate": -0.03488876782407787, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059907.8293529}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.65, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.201, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059907.8293529}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059907.9294655, "x": -88.23594367993314, "y": 40.0927744073998, "z": 202.85280040234113, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.870993816221562, "steering_wheel_angle": -0.203, "front_wheel_angle": -0.009347539997798858, "heading_rate": -0.03373975987270083, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059907.9293485}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 9.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.203, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059907.9293485}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059908.0294776, "x": -88.23594367993314, "y": 40.0927744073998, "z": 202.85280040234113, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.776406816221561, "steering_wheel_angle": -0.209, "front_wheel_angle": -0.009624584547123486, "heading_rate": -0.033198322569847394, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059908.0293543}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.83, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.209, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059908.0293543}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059908.1294389, "x": -88.2359997322325, "y": 40.0927705600462, "z": 202.86752683143425, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.704918816221562, "steering_wheel_angle": -0.214, "front_wheel_angle": -0.009855488640690276, "heading_rate": -0.03276286089605772, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059908.1293423}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 8.51, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.214, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059908.1293423}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059908.2294614, "x": -88.2359997322325, "y": 40.0927705600462, "z": 202.86752683143425, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.547446816221561, "steering_wheel_angle": -0.226, "front_wheel_angle": -0.010409783299523325, "heading_rate": -0.031596460152872666, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059908.2293718}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.226, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059908.2293718}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059908.3294318, "x": -88.2359997322325, "y": 40.0927705600462, "z": 202.86752683143425, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.449201816221562, "steering_wheel_angle": -0.236, "front_wheel_angle": -0.010871830236794713, "heading_rate": -0.03091798538002264, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059908.3293426}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.236, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059908.3293426}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059908.4295022, "x": -88.2359997322325, "y": 40.0927705600462, "z": 202.86752683143425, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.340958816221562, "steering_wheel_angle": -0.236, "front_wheel_angle": -0.010871830236794713, "heading_rate": -0.028497209052191195, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059908.429388}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.236, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059908.429388}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059908.529566, "x": -88.2359997322325, "y": 40.0927705600462, "z": 202.86752683143425, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.223742816221561, "steering_wheel_angle": -0.241, "front_wheel_angle": -0.011102899666132838, "heading_rate": -0.02624035286488335, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059908.5293949}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.241, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059908.5293949}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059908.6295838, "x": -88.23604228501264, "y": 40.09276830291143, "z": 202.87295096714547, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.142353816221561, "steering_wheel_angle": -0.251, "front_wheel_angle": -0.011565130507199158, "heading_rate": -0.02511913774398662, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059908.629388}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.251, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059908.629388}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059908.7297308, "x": -88.23604228501264, "y": 40.09276830291143, "z": 202.87295096714547, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.0417988162215615, "steering_wheel_angle": -0.256, "front_wheel_angle": -0.011796291943346152, "heading_rate": -0.02262596880968624, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059908.7293944}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.256, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059908.7293944}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059908.8294961, "x": -88.23604228501264, "y": 40.09276830291143, "z": 202.87295096714547, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9592068162215615, "steering_wheel_angle": -0.259, "front_wheel_angle": -0.011935003537068315, "heading_rate": -0.020187898135875182, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059908.8293777}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059908.8293777}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059908.9294527, "x": -88.23604228501264, "y": 40.09276830291143, "z": 202.87295096714547, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.874641816221562, "steering_wheel_angle": -0.26, "front_wheel_angle": -0.0119812431909017, "heading_rate": -0.017223861257651386, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059908.9293427}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.68, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.26, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059908.9293427}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059909.0294292, "x": -88.23604228501264, "y": 40.09276830291143, "z": 202.87295096714547, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8142068162215614, "steering_wheel_angle": -0.26, "front_wheel_angle": -0.0119812431909017, "heading_rate": -0.014836858746400785, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059909.0293415}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.17, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.26, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059909.0293415}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059909.1294355, "x": -88.23606759936455, "y": 40.09276740645063, "z": 202.89595899388584, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.745726816221562, "steering_wheel_angle": -0.26, "front_wheel_angle": -0.0119812431909017, "heading_rate": -0.011841404614635325, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059909.129343}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.53, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.26, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059909.129343}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059909.2295449, "x": -88.23606759936455, "y": 40.09276740645063, "z": 202.89595899388584, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6925268162215614, "steering_wheel_angle": -0.259, "front_wheel_angle": -0.011935003537068315, "heading_rate": -0.009184794302003259, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059909.2293756}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059909.2293756}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059909.3296776, "x": -88.23606759936455, "y": 40.09276740645063, "z": 202.89595899388584, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6455988162215616, "steering_wheel_angle": -0.263, "front_wheel_angle": -0.012119969521549536, "heading_rate": -0.006675778842773938, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059909.329347}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.263, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059909.329347}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059909.4296453, "x": -88.23606759936455, "y": 40.09276740645063, "z": 202.89595899388584, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6083178162215614, "steering_wheel_angle": -0.262, "front_wheel_angle": -0.012073726183044352, "heading_rate": -0.004244875628620185, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059909.4293966}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.262, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059909.4293966}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059909.5295198, "x": -88.23606759936455, "y": 40.09276740645063, "z": 202.89595899388584, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5821188162215614, "steering_wheel_angle": -0.262, "front_wheel_angle": -0.012073726183044352, "heading_rate": -0.002311098953359878, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059909.5293927}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.49, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.262, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059909.5293927}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059909.6297364, "x": -88.23607610565301, "y": 40.09276714448973, "z": 202.88433361925837, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5572338162215615, "steering_wheel_angle": -0.261, "front_wheel_angle": -0.012027484072861203, "heading_rate": -0.00018793850114375555, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059909.6293826}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.04, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.261, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059909.6293826}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059909.7294676, "x": -88.23607610565301, "y": 40.09276714448973, "z": 202.88433361925837, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5597988162215617, "steering_wheel_angle": -0.26, "front_wheel_angle": -0.0119812431909017, "heading_rate": -0.00042123573727951755, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059909.729371}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.09, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.26, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059909.729371}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059909.8294585, "x": -88.23607610565301, "y": 40.09276714448973, "z": 202.88433361925837, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5572338162215615, "steering_wheel_angle": -0.258, "front_wheel_angle": -0.011888765111263236, "heading_rate": -0.000185770707392638, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059909.829368}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.04, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.258, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059909.829368}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059909.9294515, "x": -88.23607610565301, "y": 40.09276714448973, "z": 202.88433361925837, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5562218162215617, "steering_wheel_angle": -0.255, "front_wheel_angle": -0.011750057201038522, "heading_rate": -9.180154674681697e-05, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059909.929343}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.255, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059909.929343}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059910.0295794, "x": -88.23607610565301, "y": 40.09276714448973, "z": 202.88433361925837, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5557188162215616, "steering_wheel_angle": -0.252, "front_wheel_angle": -0.011611360339545783, "heading_rate": -4.5358914830081184e-05, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059910.02939}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.252, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059910.02939}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059910.129456, "x": -88.23607695990738, "y": 40.09276695869153, "z": 202.87143967653196, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.252, "front_wheel_angle": -0.011611360339545783, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059910.129345}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.252, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059910.129345}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059910.229485, "x": -88.23607695990738, "y": 40.09276695869153, "z": 202.87143967653196, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.252, "front_wheel_angle": -0.011611360339545783, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059910.2293742}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.252, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059910.2293742}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059910.3294566, "x": -88.23607695990738, "y": 40.09276695869153, "z": 202.87143967653196, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.253, "front_wheel_angle": -0.011657591399236009, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059910.3293445}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.253, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059910.3293445}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059910.429533, "x": -88.23607695990738, "y": 40.09276695869153, "z": 202.87143967653196, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.263, "front_wheel_angle": -0.012119969521549536, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059910.429421}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.263, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059910.429421}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059910.5294533, "x": -88.23607695990738, "y": 40.09276695869153, "z": 202.87143967653196, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.301, "front_wheel_angle": -0.013878127539494502, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059910.5293484}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.301, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059910.5293484}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059910.62947, "x": -88.23607765029784, "y": 40.09276686018773, "z": 202.89080218671316, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.474, "front_wheel_angle": -0.021904943128487286, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059910.6293778}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.474, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059910.6293778}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059910.729461, "x": -88.23607765029784, "y": 40.09276686018773, "z": 202.89080218671316, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.755, "front_wheel_angle": -0.03502264781257071, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059910.7293658}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.755, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059910.7293658}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059910.8293698, "x": -88.23607765029784, "y": 40.09276686018773, "z": 202.89080218671316, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -1.101, "front_wheel_angle": -0.051313604365133283, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059910.8292706}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.101, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059910.8292706}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059910.9294894, "x": -88.23607765029784, "y": 40.09276686018773, "z": 202.89080218671316, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -1.552, "front_wheel_angle": -0.0727854618578966, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059910.9293535}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.552, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059910.9293535}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059911.029484, "x": -88.23607765029784, "y": 40.09276686018773, "z": 202.89080218671316, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5572338162215615, "steering_wheel_angle": -1.976, "front_wheel_angle": -0.09322517528152095, "heading_rate": -0.0014608779488235934, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059911.0293517}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.04, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.976, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059911.0293517}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059911.1297572, "x": -88.23607769436275, "y": 40.09276676611568, "z": 202.88847675996928, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5640068162215615, "steering_wheel_angle": -2.347, "front_wheel_angle": -0.11131867069497897, "heading_rate": -0.0074229421555819615, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059911.129391}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.17, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.347, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059911.129391}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059911.22948, "x": -88.23607769436275, "y": 40.09276676611568, "z": 202.88847675996928, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5567268162215617, "steering_wheel_angle": -2.7, "front_wheel_angle": -0.12872142629753341, "heading_rate": -0.0015168411004282515, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059911.2293527}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.7, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059911.2293527}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059911.3294444, "x": -88.23607769436275, "y": 40.09276676611568, "z": 202.88847675996928, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5613618162215617, "steering_wheel_angle": -3.073, "front_wheel_angle": -0.1473151106535075, "heading_rate": -0.006955786320898441, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059911.3293433}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.073, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059911.3293433}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059911.4294283, "x": -88.23607769436275, "y": 40.09276676611568, "z": 202.88847675996928, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5567268162215617, "steering_wheel_angle": -3.415, "front_wheel_angle": -0.16455473499947246, "heading_rate": -0.0019459721039194356, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059911.4293396}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059911.4293396}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059911.5294883, "x": -88.23607769436275, "y": 40.09276676611568, "z": 202.88847675996928, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5613618162215617, "steering_wheel_angle": -3.681, "front_wheel_angle": -0.17809379617438537, "heading_rate": -0.008437541519094557, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059911.5293489}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.681, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059911.5293489}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059911.6294744, "x": -88.23607797822879, "y": 40.0927666754213, "z": 202.89702767016513, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5597988162215617, "steering_wheel_angle": -3.934, "front_wheel_angle": -0.19108006796095342, "heading_rate": -0.006800628059849078, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059911.629348}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.09, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.934, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059911.629348}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059911.7294724, "x": -88.23607797822879, "y": 40.0927666754213, "z": 202.89702767016513, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5640068162215615, "steering_wheel_angle": -4.149, "front_wheel_angle": -0.2022013040090546, "heading_rate": -0.01361346857504112, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059911.7293482}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.17, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.149, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059911.7293482}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059911.8295214, "x": -88.23607797822879, "y": 40.0927666754213, "z": 202.89702767016513, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5656178162215615, "steering_wheel_angle": -4.347, "front_wheel_angle": -0.21251420201397653, "heading_rate": -0.016857209427352596, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059911.8293724}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.347, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059911.8293724}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059911.9295197, "x": -88.23607797822879, "y": 40.0927666754213, "z": 202.89702767016513, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5711178162215615, "steering_wheel_angle": -4.551, "front_wheel_angle": -0.22321232679355388, "heading_rate": -0.02660095536053221, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059911.9293747}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.551, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059911.9293747}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059912.02965, "x": -88.23607797822879, "y": 40.0927666754213, "z": 202.89702767016513, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5739428162215616, "steering_wheel_angle": -4.764, "front_wheel_angle": -0.23446285622069388, "heading_rate": -0.032656072125359495, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059912.029425}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.35, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059912.029425}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059912.1294854, "x": -88.23607797822879, "y": 40.0927666754213, "z": 202.89702767016513, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5779818162215618, "steering_wheel_angle": -5.004, "front_wheel_angle": -0.24724022603999127, "heading_rate": -0.04141007621107783, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059912.129366}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.42, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.004, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059912.129366}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059912.2294548, "x": -88.23607930092781, "y": 40.092766557763824, "z": 202.89648595171755, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5857428162215617, "steering_wheel_angle": -5.249, "front_wheel_angle": -0.26039661054227925, "heading_rate": -0.05724431457914675, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059912.229342}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.55, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.249, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059912.229342}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059912.3294725, "x": -88.23607930092781, "y": 40.092766557763824, "z": 202.89648595171755, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5906868162215617, "steering_wheel_angle": -5.57, "front_wheel_angle": -0.27781172756480704, "heading_rate": -0.07018263902148066, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059912.3293438}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.63, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.57, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059912.3293438}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059912.4294813, "x": -88.23607930092781, "y": 40.092766557763824, "z": 202.89648595171755, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5996468162215614, "steering_wheel_angle": -5.974, "front_wheel_angle": -0.30002646368076935, "heading_rate": -0.0930512653408907, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059912.4293432}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.974, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059912.4293432}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059912.529472, "x": -88.23607930092781, "y": 40.092766557763824, "z": 202.89648595171755, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6076388162215616, "steering_wheel_angle": -6.388, "front_wheel_angle": -0.32314908766022726, "heading_rate": -0.11642590101406557, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059912.5293448}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.388, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059912.5293448}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059912.629848, "x": -88.2360833080671, "y": 40.09276669301333, "z": 202.897093005129, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.615217816221562, "steering_wheel_angle": -6.751, "front_wheel_angle": -0.3437354039604252, "heading_rate": -0.13982237211230275, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059912.629521}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.751, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059912.629521}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059912.7295933, "x": -88.2360833080671, "y": 40.09276669301333, "z": 202.897093005129, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6325938162215614, "steering_wheel_angle": -7.072, "front_wheel_angle": -0.3621936817538637, "heading_rate": -0.18353424351674824, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059912.7293723}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.072, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059912.7293723}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059912.829449, "x": -88.2360833080671, "y": 40.09276669301333, "z": 202.897093005129, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6288788162215617, "steering_wheel_angle": -7.424, "front_wheel_angle": -0.3827203284357707, "heading_rate": -0.1871323641658498, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059912.829344}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.19, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.424, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059912.829344}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059912.9295495, "x": -88.2360833080671, "y": 40.09276669301333, "z": 202.897093005129, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6527178162215614, "steering_wheel_angle": -7.838, "front_wheel_angle": -0.4072630837873958, "heading_rate": -0.2527623815606275, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059912.9293642}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.838, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059912.9293642}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059913.0294242, "x": -88.2360833080671, "y": 40.09276669301333, "z": 202.897093005129, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6583668162215615, "steering_wheel_angle": -8.191, "front_wheel_angle": -0.42854880491864283, "heading_rate": -0.280187204875827, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059913.0293372}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.191, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059913.0293372}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059913.1294575, "x": -88.2360911946707, "y": 40.09276782315908, "z": 202.9029443725308, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6750468162215615, "steering_wheel_angle": -8.577, "front_wheel_angle": -0.4522230368924106, "heading_rate": -0.33588500604471594, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059913.1293643}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.577, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059913.1293643}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059913.229478, "x": -88.2360911946707, "y": 40.09276782315908, "z": 202.9029443725308, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6871988162215614, "steering_wheel_angle": -8.99, "front_wheel_angle": -0.47803995078529476, "heading_rate": -0.38656765171161167, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059913.2293746}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.91, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.99, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059913.2293746}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059913.3295934, "x": -88.2360911946707, "y": 40.09276782315908, "z": 202.9029443725308, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6961188162215617, "steering_wheel_angle": -9.397, "front_wheel_angle": -0.5040037673708885, "heading_rate": -0.433023557731869, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059913.3293974}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.01, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.397, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059913.3293974}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059913.4294772, "x": -88.2360911946707, "y": 40.09276782315908, "z": 202.9029443725308, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7145588162215617, "steering_wheel_angle": -9.743, "front_wheel_angle": -0.5265083728243672, "heading_rate": -0.5017703746174933, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059913.4293497}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.21, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.743, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059913.4293497}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059913.529461, "x": -88.2360911946707, "y": 40.09276782315908, "z": 202.9029443725308, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7260068162215614, "steering_wheel_angle": -10.03, "front_wheel_angle": -0.5454936933484523, "heading_rate": -0.5523938845495332, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059913.5293453}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.33, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.03, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059913.5293453}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059913.629536, "x": -88.23610286753774, "y": 40.09277145252481, "z": 202.90031538544747, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7397268162215616, "steering_wheel_angle": -10.32, "front_wheel_angle": -0.5649856053836634, "heading_rate": -0.6116305139024089, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059913.629405}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.47, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.32, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059913.629405}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059913.7294314, "x": -88.23610286753774, "y": 40.09277145252481, "z": 202.90031538544747, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7497668162215616, "steering_wheel_angle": -10.574, "front_wheel_angle": -0.5823244181827265, "heading_rate": -0.6610679352147497, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059913.7293375}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.574, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059913.7293375}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059913.8294911, "x": -88.23610286753774, "y": 40.09277145252481, "z": 202.90031538544747, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7672938162215615, "steering_wheel_angle": -10.826, "front_wheel_angle": -0.5997843025507691, "heading_rate": -0.7319013098349985, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059913.8293722}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.74, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.826, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059913.8293722}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744059913.929464, "x": -88.23610286753774, "y": 40.09277145252481, "z": 202.90031538544747, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.782161816221562, "steering_wheel_angle": -11.059, "front_wheel_angle": -0.6161663369102495, "heading_rate": -0.7966543770093883, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744059913.929336}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.88, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -11.059, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744059913.929336}
diff --git a/testing/racing_logs/gg_data/gg_diagram.png b/testing/racing_logs/gg_data/gg_diagram.png
new file mode 100644
index 000000000..13dec50b3
Binary files /dev/null and b/testing/racing_logs/gg_data/gg_diagram.png differ
diff --git a/testing/racing_logs/gg_data/meta.yaml b/testing/racing_logs/gg_data/meta.yaml
new file mode 100644
index 000000000..cbcb3b97e
--- /dev/null
+++ b/testing/racing_logs/gg_data/meta.yaml
@@ -0,0 +1,19 @@
+events:
+- description: Ctrl+C pressed, switching to recovery mode
+ time: 1744059914.022588
+ vehicle_time: 1744059913.929336
+- description: Mission execution ended
+ time: 1744059914.02777
+ vehicle_time: 1744059913.929336
+exit_reason: normal exit
+git_branch: racing
+git_commit_id: 2e36aeb7a55246289008a8f0a7de7f84bdbec5e6
+pipelines:
+- name: drive
+ time: 1744059565.4285564
+ vehicle_time: 1744059565.3283975
+- name: recovery
+ time: 1744059914.0236647
+ vehicle_time: 1744059913.929336
+start_time: 1744059565.3068607
+start_time_human_readable: '2025-04-07 15:59:25'
diff --git a/testing/racing_logs/gg_data/settings.yaml b/testing/racing_logs/gg_data/settings.yaml
new file mode 100644
index 000000000..7edac7f70
--- /dev/null
+++ b/testing/racing_logs/gg_data/settings.yaml
@@ -0,0 +1,300 @@
+control:
+ longitudinal_control:
+ pid_d: 0.0
+ pid_i: 0.03
+ pid_p: 0.8
+ pure_pursuit:
+ crosstrack_gain: 0.3
+ desired_speed: racing
+ launch_control: 0
+ lookahead: 2.0
+ lookahead_scale: 2.0
+ recovery:
+ brake_amount: 0.5
+ brake_speed: 2.0
+model_predictive_controller:
+ dt: 0.1
+ lookahead: 20
+planning:
+ longitudinal_plan:
+ acceleration: 0.5
+ deceleration: 2.0
+ desired_speed: 1.0
+ max_deceleration: 6.0
+ min_deceleration: 0.5
+ mode: real
+ planner: dt
+ yield_deceleration: 0.5
+ yielder: expert
+run:
+ 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:
+ - all
+ 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: Gather data from the GEM vehicle as the operator is driving it manually
+ drive:
+ perception:
+ perception_normalization: StandardPerceptionNormalizer
+ state_estimation: GNSSStateEstimator
+ planning:
+ motion_planning: RouteToTrajectoryPlanner
+ route_planning:
+ args:
+ - GEMstack/knowledge/routes/xyhead_highbay_backlot_p.csv
+ type: StaticRoutePlanner
+ log:
+ components:
+ - state_estimation
+ ros_topics: []
+ vehicle_interface: true
+ mission_execution: StandardExecutor
+ mode: hardware
+ name: launch/gather_data.yaml
+ recovery:
+ planning:
+ trajectory_tracking: recovery.StopTrajectoryTracker
+ replay:
+ components: []
+ log: null
+ ros_topics: []
+ require_engaged: false
+ variants:
+ log_ros:
+ run:
+ 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
+ vehicle_interface: gem_hardware.GEMHardwareInterface
+simulator:
+ dt: 0.01
+ gnss_emulator:
+ dt: 0.05
+ real_time_multiplier: 1.0
+vehicle:
+ calibration:
+ calibration_date: '2025-02-25'
+ front_camera:
+ center_position:
+ - 1.75864913
+ - 0.01238124
+ - 1.54408419
+ reference: rear_axle_center
+ rotation:
+ - - 0.00349517
+ - -0.03239524
+ - 0.99946903
+ - - -0.99996547
+ - 0.00742285
+ - 0.0037375
+ - - -0.00753999
+ - -0.99944757
+ - -0.03236817
+ gnss_location:
+ - 1.1
+ - 0
+ - 1.62
+ gnss_yaw: 0.0
+ rear_axle_height: 0.2794
+ reference: rear_axle_center
+ top_lidar:
+ position:
+ - 1.1
+ - 0.03773044170906172
+ - 1.9525244316515322
+ reference: rear_axle_center
+ rotation:
+ - - 0.99941328
+ - 0.02547416
+ - 0.02289458
+ - - -0.02530855
+ - 0.99965159
+ - -0.00749488
+ - - -0.02307753
+ - 0.00691106
+ - 0.99970979
+ control_defaults:
+ accelerator_pedal_speed: 3.0
+ brake_pedal_speed: 3.0
+ steering_wheel_speed: 4.0
+ dynamics:
+ acceleration_deadband: 0.1
+ acceleration_model: hang_v1
+ accelerator_active_range:
+ - 0.2
+ - 1.0
+ aerodynamic_drag_coefficient: 0.01
+ brake_active_range:
+ - 0.5
+ - 1
+ gravity: 9.81
+ internal_dry_deceleration: 0.2
+ internal_viscous_deceleration: 0.05
+ lateral_friction: 1.0
+ longitudinal_friction: 1.0
+ mass: 700.0
+ max_accelerator_acceleration:
+ - 0.0
+ - 5.0
+ max_accelerator_acceleration_reverse: 2.5
+ max_accelerator_power:
+ - 0.0
+ - 5000.0
+ max_accelerator_power_reverse: 5000.0
+ max_brake_deceleration: 8.0
+ pedal_mapping_function: linear
+ velocity_scaling_factor: 0.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/gem/racing2/src/GEMstack/GEMstack/knowledge/vehicle/model/gem_e4.urdf
+ wheel_radius: 0.33
+ wheelbase: 2.56
+ width: 1.7
+ limits:
+ max_acceleration: 3.0
+ max_accelerator_pedal: 1.0
+ max_brake_pedal: 1.0
+ max_deceleration: 5.0
+ max_reverse_speed: 2.5
+ max_speed: 10.0
+ max_steering_rate: 4.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/testing/racing_logs/launch_control/PurePursuitTrajectoryTracker_debug.csv b/testing/racing_logs/launch_control/PurePursuitTrajectoryTracker_debug.csv
new file mode 100644
index 000000000..aea52ecf3
--- /dev/null
+++ b/testing/racing_logs/launch_control/PurePursuitTrajectoryTracker_debug.csv
@@ -0,0 +1,857 @@
+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)
+1744060568.3573735,0.1011655330657959,0.0,1744060568.3573754,0.1011655330657959,0.0,1744060568.3573775,0.1011655330657959,0.0,1744060568.3573802,0.1011655330657959,56568542496.923805,1744060568.357381,0.1011655330657959,0.0,1744060568.357384,0.1011655330657959,0.0,1744060568.3573854,0.1011655330657959,0.0,1744060568.3573866,0.1011655330657959,0.0,1744060568.357388,0.1011655330657959,10,1744060568.3573892,0.1011655330657959,0.0,1744060568.3573906,0.1011655330657959,-22627416989.969524,1744060568.3573918,0.1011655330657959,0.0,1744060568.3573928,0.1011655330657959,28284271247.461903
+1744060568.3769274,0.1212303638458252,0.0,1744060568.3769298,0.1212303638458252,0.0,1744060568.376932,0.1212303638458252,0.0,1744060568.3769343,0.1212303638458252,56568542496.923805,1744060568.3769355,0.1212303638458252,0.0,1744060568.3769367,0.1212303638458252,0.0,1744060568.3769379,0.1212303638458252,0.0,1744060568.3769393,0.1212303638458252,0.0,1744060568.3769405,0.1212303638458252,10,1744060568.3769417,0.1212303638458252,0.0,1744060568.3769426,0.1212303638458252,-22627416989.969524,1744060568.3769438,0.1212303638458252,0.0,1744060568.3769453,0.1212303638458252,28284271247.461903
+1744060568.3972113,0.14127182960510254,0.0,1744060568.3972147,0.14127182960510254,0.0,1744060568.3972182,0.14127182960510254,0.0,1744060568.3972225,0.14127182960510254,56568542496.923805,1744060568.3972247,0.14127182960510254,0.0,1744060568.397227,0.14127182960510254,0.0,1744060568.3972297,0.14127182960510254,0.0,1744060568.3972318,0.14127182960510254,0.0,1744060568.3972344,0.14127182960510254,10,1744060568.3972368,0.14127182960510254,0.0,1744060568.397239,0.14127182960510254,-22627416989.969524,1744060568.397241,0.14127182960510254,0.0,1744060568.397244,0.14127182960510254,28284271247.461903
+1744060568.4171715,0.16130685806274414,0.0,1744060568.4171739,0.16130685806274414,0.0,1744060568.4171762,0.16130685806274414,0.0,1744060568.4171786,0.16130685806274414,56568542496.923805,1744060568.4171798,0.16130685806274414,0.0,1744060568.4171813,0.16130685806274414,0.0,1744060568.4171827,0.16130685806274414,0.0,1744060568.4171846,0.16130685806274414,0.0,1744060568.4171863,0.16130685806274414,10,1744060568.4171872,0.16130685806274414,0.0,1744060568.4171884,0.16130685806274414,-22627416989.969524,1744060568.4171896,0.16130685806274414,0.0,1744060568.417191,0.16130685806274414,28284271247.461903
+1744060568.4371166,0.18139982223510742,0.0,1744060568.4371192,0.18139982223510742,0.0,1744060568.4371216,0.18139982223510742,0.0,1744060568.437124,0.18139982223510742,56568542496.923805,1744060568.4371257,0.18139982223510742,0.0,1744060568.437127,0.18139982223510742,0.0,1744060568.4371283,0.18139982223510742,0.0,1744060568.4371297,0.18139982223510742,0.0,1744060568.4371307,0.18139982223510742,10,1744060568.4371321,0.18139982223510742,0.0,1744060568.4371333,0.18139982223510742,-22627416989.969524,1744060568.4371345,0.18139982223510742,0.0,1744060568.437136,0.18139982223510742,28284271247.461903
+1744060568.4589448,0.20140290260314941,0.0,1744060568.4589484,0.20140290260314941,0.0,1744060568.4589515,0.20140290260314941,0.0,1744060568.4589548,0.20140290260314941,56568542496.923805,1744060568.4589565,0.20140290260314941,0.0,1744060568.4589586,0.20140290260314941,0.0,1744060568.458961,0.20140290260314941,0.0,1744060568.458963,0.20140290260314941,0.0,1744060568.4589648,0.20140290260314941,10,1744060568.458966,0.20140290260314941,0.0,1744060568.4589672,0.20140290260314941,-22627416989.969524,1744060568.4589698,0.20140290260314941,0.0,1744060568.458971,0.20140290260314941,28284271247.461903
+1744060568.4769824,0.22126221656799316,0.0,1744060568.4769843,0.22126221656799316,0.0,1744060568.4769866,0.22126221656799316,0.0,1744060568.476989,0.22126221656799316,56568542496.923805,1744060568.4769902,0.22126221656799316,0.0,1744060568.4769914,0.22126221656799316,0.0,1744060568.4769928,0.22126221656799316,0.0,1744060568.4769938,0.22126221656799316,0.0,1744060568.476995,0.22126221656799316,10,1744060568.4769964,0.22126221656799316,0.0,1744060568.4769974,0.22126221656799316,-22627416989.969524,1744060568.4769986,0.22126221656799316,0.0,1744060568.4769998,0.22126221656799316,28284271247.461903
+1744060568.4971476,0.2412869930267334,0.0,1744060568.4971497,0.2412869930267334,0.0,1744060568.497152,0.2412869930267334,0.0,1744060568.4971542,0.2412869930267334,56568542496.923805,1744060568.4971557,0.2412869930267334,0.0,1744060568.4971569,0.2412869930267334,0.0,1744060568.497158,0.2412869930267334,0.0,1744060568.4971595,0.2412869930267334,0.0,1744060568.4971607,0.2412869930267334,10,1744060568.4971616,0.2412869930267334,0.0,1744060568.497163,0.2412869930267334,-22627416989.969524,1744060568.497164,0.2412869930267334,0.0,1744060568.497165,0.2412869930267334,28284271247.461903
+1744060568.5172236,0.26126885414123535,0.0,1744060568.517226,0.26126885414123535,0.0,1744060568.5172284,0.26126885414123535,0.0,1744060568.5172307,0.26126885414123535,56568542496.923805,1744060568.5172322,0.26126885414123535,0.0,1744060568.5172334,0.26126885414123535,0.0,1744060568.5172348,0.26126885414123535,0.0,1744060568.5172365,0.26126885414123535,0.0,1744060568.5172377,0.26126885414123535,10,1744060568.517239,0.26126885414123535,0.0,1744060568.51724,0.26126885414123535,-22627416989.969524,1744060568.5172412,0.26126885414123535,0.0,1744060568.5172424,0.26126885414123535,28284271247.461903
+1744060568.537002,0.2812843322753906,0.0,1744060568.537004,0.2812843322753906,0.0,1744060568.5370066,0.2812843322753906,0.0,1744060568.537009,0.2812843322753906,56568542496.923805,1744060568.53701,0.2812843322753906,0.0,1744060568.5370111,0.2812843322753906,0.0,1744060568.5370126,0.2812843322753906,0.0,1744060568.5370138,0.2812843322753906,0.0,1744060568.5370152,0.2812843322753906,10,1744060568.5370166,0.2812843322753906,0.0,1744060568.5370178,0.2812843322753906,-22627416989.969524,1744060568.5370193,0.2812843322753906,0.0,1744060568.5370204,0.2812843322753906,28284271247.461903
+1744060568.5577884,0.3012852668762207,0.0,1744060568.5577905,0.3012852668762207,0.0,1744060568.5577927,0.3012852668762207,0.0,1744060568.557795,0.3012852668762207,56568542496.923805,1744060568.557796,0.3012852668762207,0.0,1744060568.5577977,0.3012852668762207,0.0,1744060568.5578163,0.3012852668762207,0.0,1744060568.557818,0.3012852668762207,0.0,1744060568.5578191,0.3012852668762207,10,1744060568.55782,0.3012852668762207,0.0,1744060568.5578213,0.3012852668762207,-22627416989.969524,1744060568.5578222,0.3012852668762207,0.0,1744060568.5578232,0.3012852668762207,28284271247.461903
+1744060568.577159,0.32123732566833496,0.0,1744060568.577161,0.32123732566833496,0.0,1744060568.5771632,0.32123732566833496,0.0,1744060568.5771656,0.32123732566833496,56568542496.923805,1744060568.5771668,0.32123732566833496,0.0,1744060568.5771682,0.32123732566833496,0.0,1744060568.5771694,0.32123732566833496,0.0,1744060568.5771704,0.32123732566833496,0.0,1744060568.5771718,0.32123732566833496,10,1744060568.5771728,0.32123732566833496,0.0,1744060568.5771737,0.32123732566833496,-22627416989.969524,1744060568.5771751,0.32123732566833496,0.0,1744060568.577176,0.32123732566833496,28284271247.461903
+1744060568.5972939,0.3412597179412842,0.0,1744060568.5972962,0.3412597179412842,0.0,1744060568.5972984,0.3412597179412842,0.0,1744060568.5973008,0.3412597179412842,56568542496.923805,1744060568.5973017,0.3412597179412842,0.0,1744060568.5973032,0.3412597179412842,0.0,1744060568.5973043,0.3412597179412842,0.0,1744060568.5973058,0.3412597179412842,0.0,1744060568.597307,0.3412597179412842,10,1744060568.5973082,0.3412597179412842,0.0,1744060568.597309,0.3412597179412842,-22627416989.969524,1744060568.5973103,0.3412597179412842,0.0,1744060568.5973115,0.3412597179412842,28284271247.461903
+1744060568.6175284,0.3615274429321289,0.0,1744060568.6175303,0.3615274429321289,0.0,1744060568.617533,0.3615274429321289,0.0,1744060568.617535,0.3615274429321289,56568542496.923805,1744060568.6175363,0.3615274429321289,0.0,1744060568.6175377,0.3615274429321289,0.0,1744060568.617539,0.3615274429321289,0.0,1744060568.6175404,0.3615274429321289,0.0,1744060568.6175416,0.3615274429321289,10,1744060568.6175427,0.3615274429321289,0.0,1744060568.6175437,0.3615274429321289,-22627416989.969524,1744060568.617545,0.3615274429321289,0.0,1744060568.617546,0.3615274429321289,28284271247.461903
+1744060568.6378303,0.3817250728607178,0.0,1744060568.6378329,0.3817250728607178,0.0,1744060568.6378362,0.3817250728607178,0.0,1744060568.6378398,0.3817250728607178,56568542496.923805,1744060568.6378605,0.3817250728607178,0.0,1744060568.6378627,0.3817250728607178,0.0,1744060568.6378644,0.3817250728607178,0.0,1744060568.6378665,0.3817250728607178,0.0,1744060568.6378684,0.3817250728607178,10,1744060568.6378698,0.3817250728607178,0.0,1744060568.6378715,0.3817250728607178,-22627416989.969524,1744060568.6378732,0.3817250728607178,0.0,1744060568.6378748,0.3817250728607178,28284271247.461903
+1744060568.6601079,0.4013385772705078,0.0,1744060568.6601124,0.4013385772705078,0.0,1744060568.6601167,0.4013385772705078,0.0,1744060568.6601207,0.4013385772705078,56568542496.923805,1744060568.6601236,0.4013385772705078,0.0,1744060568.6601276,0.4013385772705078,0.0,1744060568.6601307,0.4013385772705078,0.0,1744060568.6601338,0.4013385772705078,0.0,1744060568.6601367,0.4013385772705078,10,1744060568.6601388,0.4013385772705078,0.0,1744060568.6601415,0.4013385772705078,-22627416989.969524,1744060568.660144,0.4013385772705078,0.0,1744060568.6601474,0.4013385772705078,28284271247.461903
+1744060568.677053,0.42128539085388184,0.0,1744060568.6770551,0.42128539085388184,0.0,1744060568.6770575,0.42128539085388184,0.0,1744060568.6770601,0.42128539085388184,56568542496.923805,1744060568.6770613,0.42128539085388184,0.0,1744060568.677063,0.42128539085388184,0.0,1744060568.6770642,0.42128539085388184,0.0,1744060568.6770656,0.42128539085388184,0.0,1744060568.677067,0.42128539085388184,10,1744060568.6770682,0.42128539085388184,0.0,1744060568.6770697,0.42128539085388184,-22627416989.969524,1744060568.6770709,0.42128539085388184,0.0,1744060568.677072,0.42128539085388184,28284271247.461903
+1744060568.697148,0.44127392768859863,0.0,1744060568.6971502,0.44127392768859863,0.0,1744060568.6971521,0.44127392768859863,0.0,1744060568.6971545,0.44127392768859863,56568542496.923805,1744060568.697156,0.44127392768859863,0.0,1744060568.6971571,0.44127392768859863,0.0,1744060568.6971586,0.44127392768859863,0.0,1744060568.6971598,0.44127392768859863,0.0,1744060568.697161,0.44127392768859863,10,1744060568.697162,0.44127392768859863,0.0,1744060568.697163,0.44127392768859863,-22627416989.969524,1744060568.697164,0.44127392768859863,0.0,1744060568.697165,0.44127392768859863,28284271247.461903
+1744060568.7169604,0.4612400531768799,0.0,1744060568.7169628,0.4612400531768799,0.0,1744060568.716965,0.4612400531768799,0.0,1744060568.7169673,0.4612400531768799,56568542496.923805,1744060568.7169688,0.4612400531768799,0.0,1744060568.71697,0.4612400531768799,0.0,1744060568.7169712,0.4612400531768799,0.0,1744060568.7169726,0.4612400531768799,0.0,1744060568.7169738,0.4612400531768799,10,1744060568.7169752,0.4612400531768799,0.0,1744060568.7169762,0.4612400531768799,-22627416989.969524,1744060568.7169778,0.4612400531768799,0.0,1744060568.7169795,0.4612400531768799,28284271247.461903
+1744060568.7377052,0.48160815238952637,0.0,1744060568.7377074,0.48160815238952637,0.0,1744060568.7377098,0.48160815238952637,0.0,1744060568.7377124,0.48160815238952637,56568542496.923805,1744060568.7377133,0.48160815238952637,0.0,1744060568.7377148,0.48160815238952637,0.0,1744060568.737716,0.48160815238952637,0.0,1744060568.7377174,0.48160815238952637,0.0,1744060568.7377372,0.48160815238952637,10,1744060568.7377386,0.48160815238952637,0.0,1744060568.7377396,0.48160815238952637,-22627416989.969524,1744060568.7377405,0.48160815238952637,0.0,1744060568.7377417,0.48160815238952637,28284271247.461903
+1744060568.7576265,0.5012643337249756,-0.0021229806224089573,1744060568.7576287,0.5012643337249756,0.0015435691132928693,1744060568.7576308,0.5012643337249756,0.0,1744060568.757633,0.5012643337249756,56568542496.923805,1744060568.7576342,0.5012643337249756,0.0,1744060568.7576363,0.5012643337249756,-2.72867046800216e-14,1744060568.7576382,0.5012643337249756,-0.0015575317190694303,1744060568.7576396,0.5012643337249756,-2.242845675301218e-24,1744060568.7576416,0.5012643337249756,10,1744060568.7576432,0.5012643337249756,0.0,1744060568.757645,0.5012643337249756,-22627416989.969524,1744060568.7576466,0.5012643337249756,0.0,1744060568.7576485,0.5012643337249756,28284271247.461903
+1744060568.7776055,0.5213263034820557,-0.0021229806224089573,1744060568.777608,0.5213263034820557,0.0015435691132928693,1744060568.7776103,0.5213263034820557,0.0,1744060568.7776124,0.5213263034820557,56568542496.923805,1744060568.7776139,0.5213263034820557,0.0,1744060568.777615,0.5213263034820557,-2.72867046800216e-14,1744060568.7776165,0.5213263034820557,-0.0015575317190694303,1744060568.7776177,0.5213263034820557,-2.242845675301218e-24,1744060568.777619,0.5213263034820557,10,1744060568.77762,0.5213263034820557,0.0,1744060568.777621,0.5213263034820557,-22627416989.969524,1744060568.7776222,0.5213263034820557,0.0,1744060568.7776234,0.5213263034820557,28284271247.461903
+1744060568.7971485,0.5412461757659912,-0.0021229806224089573,1744060568.797151,0.5412461757659912,0.0015435691132928693,1744060568.7971532,0.5412461757659912,0.0,1744060568.7971559,0.5412461757659912,56568542496.923805,1744060568.797157,0.5412461757659912,0.0,1744060568.7971585,0.5412461757659912,-2.72867046800216e-14,1744060568.7971601,0.5412461757659912,-0.0015575317190694303,1744060568.7971616,0.5412461757659912,-2.242845675301218e-24,1744060568.797163,0.5412461757659912,10,1744060568.7971644,0.5412461757659912,0.0,1744060568.7971659,0.5412461757659912,-22627416989.969524,1744060568.797167,0.5412461757659912,0.0,1744060568.7971685,0.5412461757659912,28284271247.461903
+1744060568.817319,0.5612421035766602,-0.0021229806224089573,1744060568.817321,0.5612421035766602,0.0015435691132928693,1744060568.8173232,0.5612421035766602,0.0,1744060568.8173258,0.5612421035766602,56568542496.923805,1744060568.8173268,0.5612421035766602,0.0,1744060568.8173285,0.5612421035766602,-2.72867046800216e-14,1744060568.8173294,0.5612421035766602,-0.0015575317190694303,1744060568.8173306,0.5612421035766602,-2.242845675301218e-24,1744060568.8173323,0.5612421035766602,10,1744060568.8173332,0.5612421035766602,0.0,1744060568.8173344,0.5612421035766602,-22627416989.969524,1744060568.8173356,0.5612421035766602,0.0,1744060568.8173368,0.5612421035766602,28284271247.461903
+1744060568.837101,0.5813338756561279,-0.0021229806224089573,1744060568.8371034,0.5813338756561279,0.0015435691132928693,1744060568.837106,0.5813338756561279,0.0,1744060568.8371084,0.5813338756561279,56568542496.923805,1744060568.8371096,0.5813338756561279,0.0,1744060568.837111,0.5813338756561279,-2.72867046800216e-14,1744060568.8371124,0.5813338756561279,-0.0015575317190694303,1744060568.8371136,0.5813338756561279,-2.242845675301218e-24,1744060568.8371148,0.5813338756561279,10,1744060568.837116,0.5813338756561279,0.0,1744060568.8371172,0.5813338756561279,-22627416989.969524,1744060568.8371184,0.5813338756561279,0.0,1744060568.8371198,0.5813338756561279,28284271247.461903
+1744060568.8587773,0.601264476776123,-0.0021229806224089573,1744060568.85878,0.601264476776123,0.0015435691132928693,1744060568.858783,0.601264476776123,0.0,1744060568.8587859,0.601264476776123,56568542496.923805,1744060568.8587878,0.601264476776123,0.0,1744060568.85879,0.601264476776123,-2.72867046800216e-14,1744060568.8587925,0.601264476776123,-0.0015575317190694303,1744060568.8587947,0.601264476776123,-2.242845675301218e-24,1744060568.8587976,0.601264476776123,10,1744060568.8587995,0.601264476776123,0.0,1744060568.8588016,0.601264476776123,-22627416989.969524,1744060568.8588037,0.601264476776123,0.0,1744060568.8588061,0.601264476776123,28284271247.461903
+1744060568.877655,0.6212809085845947,-0.0021229806224089573,1744060568.8776574,0.6212809085845947,0.0015435691132928693,1744060568.8776596,0.6212809085845947,0.0,1744060568.877662,0.6212809085845947,56568542496.923805,1744060568.8776631,0.6212809085845947,0.0,1744060568.8776648,0.6212809085845947,-2.72867046800216e-14,1744060568.877666,0.6212809085845947,-0.0015575317190694303,1744060568.8776674,0.6212809085845947,-2.242845675301218e-24,1744060568.8776686,0.6212809085845947,10,1744060568.8776698,0.6212809085845947,0.0,1744060568.8776712,0.6212809085845947,-22627416989.969524,1744060568.8776724,0.6212809085845947,0.0,1744060568.8776734,0.6212809085845947,28284271247.461903
+1744060568.8973322,0.6412901878356934,-0.0021229806224089573,1744060568.897335,0.6412901878356934,0.0015435691132928693,1744060568.897338,0.6412901878356934,0.0,1744060568.8973403,0.6412901878356934,56568542496.923805,1744060568.897342,0.6412901878356934,0.0,1744060568.8973436,0.6412901878356934,-2.72867046800216e-14,1744060568.897345,0.6412901878356934,-0.0015575317190694303,1744060568.8973465,0.6412901878356934,-2.242845675301218e-24,1744060568.8973489,0.6412901878356934,10,1744060568.8973505,0.6412901878356934,0.0,1744060568.897352,0.6412901878356934,-22627416989.969524,1744060568.897353,0.6412901878356934,0.0,1744060568.8973541,0.6412901878356934,28284271247.461903
+1744060568.9170015,0.6612441539764404,-0.0021229806224089573,1744060568.9170036,0.6612441539764404,0.0015435691132928693,1744060568.917006,0.6612441539764404,0.0,1744060568.9170082,0.6612441539764404,56568542496.923805,1744060568.9170094,0.6612441539764404,0.0,1744060568.9170108,0.6612441539764404,-2.72867046800216e-14,1744060568.917012,0.6612441539764404,-0.0015575317190694303,1744060568.9170132,0.6612441539764404,-2.242845675301218e-24,1744060568.9170146,0.6612441539764404,10,1744060568.9170156,0.6612441539764404,0.0,1744060568.9170165,0.6612441539764404,-22627416989.969524,1744060568.917018,0.6612441539764404,0.0,1744060568.917019,0.6612441539764404,28284271247.461903
+1744060568.9372709,0.6812701225280762,-0.0021229806224089573,1744060568.9372733,0.6812701225280762,0.0015435691132928693,1744060568.937276,0.6812701225280762,0.0,1744060568.9372785,0.6812701225280762,56568542496.923805,1744060568.9372797,0.6812701225280762,0.0,1744060568.9372811,0.6812701225280762,-2.72867046800216e-14,1744060568.9372826,0.6812701225280762,-0.0015575317190694303,1744060568.9372835,0.6812701225280762,-2.242845675301218e-24,1744060568.937285,0.6812701225280762,10,1744060568.9372861,0.6812701225280762,0.0,1744060568.937287,0.6812701225280762,-22627416989.969524,1744060568.9372885,0.6812701225280762,0.0,1744060568.9372895,0.6812701225280762,28284271247.461903
+1744060568.9573424,0.7012403011322021,-0.0021229806224089573,1744060568.9573445,0.7012403011322021,0.0015435691132928693,1744060568.9573467,0.7012403011322021,0.0,1744060568.9573488,0.7012403011322021,56568542496.923805,1744060568.9573503,0.7012403011322021,0.0,1744060568.9573514,0.7012403011322021,-2.72867046800216e-14,1744060568.9573526,0.7012403011322021,-0.0015575317190694303,1744060568.9573538,0.7012403011322021,-2.242845675301218e-24,1744060568.957355,0.7012403011322021,10,1744060568.9573562,0.7012403011322021,0.0,1744060568.9573574,0.7012403011322021,-22627416989.969524,1744060568.9573586,0.7012403011322021,0.0,1744060568.9573596,0.7012403011322021,28284271247.461903
+1744060568.9770322,0.7212362289428711,-0.0021229806224089573,1744060568.9770343,0.7212362289428711,0.0015435691132928693,1744060568.977037,0.7212362289428711,0.0,1744060568.9770396,0.7212362289428711,56568542496.923805,1744060568.977041,0.7212362289428711,0.0,1744060568.9770427,0.7212362289428711,-2.72867046800216e-14,1744060568.9770439,0.7212362289428711,-0.0015575317190694303,1744060568.9770455,0.7212362289428711,-2.242845675301218e-24,1744060568.977047,0.7212362289428711,10,1744060568.9770489,0.7212362289428711,0.0,1744060568.97705,0.7212362289428711,-22627416989.969524,1744060568.9770517,0.7212362289428711,0.0,1744060568.977053,0.7212362289428711,28284271247.461903
+1744060568.9970675,0.7412412166595459,-0.0021229806224089573,1744060568.9970696,0.7412412166595459,0.0015435691132928693,1744060568.997072,0.7412412166595459,0.0,1744060568.9970741,0.7412412166595459,56568542496.923805,1744060568.997075,0.7412412166595459,0.0,1744060568.9970765,0.7412412166595459,-2.72867046800216e-14,1744060568.9970777,0.7412412166595459,-0.0015575317190694303,1744060568.9970791,0.7412412166595459,-2.242845675301218e-24,1744060568.9970803,0.7412412166595459,10,1744060568.9970813,0.7412412166595459,0.0,1744060568.9970827,0.7412412166595459,-22627416989.969524,1744060568.997084,0.7412412166595459,0.0,1744060568.9970849,0.7412412166595459,28284271247.461903
+1744060569.0169244,0.7612273693084717,-0.0021229806224089573,1744060569.0169265,0.7612273693084717,0.0015435691132928693,1744060569.0169284,0.7612273693084717,0.0,1744060569.0169308,0.7612273693084717,56568542496.923805,1744060569.0169318,0.7612273693084717,0.0,1744060569.0169332,0.7612273693084717,-2.72867046800216e-14,1744060569.0169344,0.7612273693084717,-0.0015575317190694303,1744060569.0169356,0.7612273693084717,-2.242845675301218e-24,1744060569.016937,0.7612273693084717,10,1744060569.016938,0.7612273693084717,0.0,1744060569.016939,0.7612273693084717,-22627416989.969524,1744060569.0169404,0.7612273693084717,0.0,1744060569.0169413,0.7612273693084717,28284271247.461903
+1744060569.0375788,0.7812752723693848,-0.0021229806224089573,1744060569.037582,0.7812752723693848,0.0015435691132928693,1744060569.0375853,0.7812752723693848,0.0,1744060569.0375888,0.7812752723693848,56568542496.923805,1744060569.0375905,0.7812752723693848,0.0,1744060569.037593,0.7812752723693848,-2.72867046800216e-14,1744060569.0375946,0.7812752723693848,-0.0015575317190694303,1744060569.0375967,0.7812752723693848,-2.242845675301218e-24,1744060569.0375986,0.7812752723693848,10,1744060569.0376008,0.7812752723693848,0.0,1744060569.037603,0.7812752723693848,-22627416989.969524,1744060569.0376043,0.7812752723693848,0.0,1744060569.0376067,0.7812752723693848,28284271247.461903
+1744060569.05762,0.8012521266937256,-0.0021229806224089573,1744060569.0576222,0.8012521266937256,0.0015435691132928693,1744060569.0576248,0.8012521266937256,0.0,1744060569.0576272,0.8012521266937256,56568542496.923805,1744060569.0576282,0.8012521266937256,0.0,1744060569.0576296,0.8012521266937256,-2.72867046800216e-14,1744060569.057631,0.8012521266937256,-0.0015575317190694303,1744060569.0576322,0.8012521266937256,-2.242845675301218e-24,1744060569.0576336,0.8012521266937256,10,1744060569.0576346,0.8012521266937256,0.0,1744060569.0576355,0.8012521266937256,-22627416989.969524,1744060569.057637,0.8012521266937256,0.0,1744060569.0576382,0.8012521266937256,28284271247.461903
+1744060569.0769494,0.8212628364562988,-0.0021229806224089573,1744060569.0769513,0.8212628364562988,0.0015435691132928693,1744060569.0769536,0.8212628364562988,0.0,1744060569.0769558,0.8212628364562988,56568542496.923805,1744060569.0769572,0.8212628364562988,0.0,1744060569.0769584,0.8212628364562988,-2.72867046800216e-14,1744060569.0769598,0.8212628364562988,-0.0015575317190694303,1744060569.076961,0.8212628364562988,-2.242845675301218e-24,1744060569.0769622,0.8212628364562988,10,1744060569.0769634,0.8212628364562988,0.0,1744060569.0769646,0.8212628364562988,-22627416989.969524,1744060569.0769656,0.8212628364562988,0.0,1744060569.0769668,0.8212628364562988,28284271247.461903
+1744060569.0976026,0.8412759304046631,-0.0021229806224089573,1744060569.0976048,0.8412759304046631,0.0015435691132928693,1744060569.0976071,0.8412759304046631,0.0,1744060569.0976095,0.8412759304046631,56568542496.923805,1744060569.0976107,0.8412759304046631,0.0,1744060569.0976121,0.8412759304046631,-2.72867046800216e-14,1744060569.0976133,0.8412759304046631,-0.0015575317190694303,1744060569.0976145,0.8412759304046631,-2.242845675301218e-24,1744060569.097616,0.8412759304046631,10,1744060569.0976171,0.8412759304046631,0.0,1744060569.097618,0.8412759304046631,-22627416989.969524,1744060569.0976198,0.8412759304046631,0.0,1744060569.0976207,0.8412759304046631,28284271247.461903
+1744060569.1174004,0.8612685203552246,-0.0021229806224089573,1744060569.1174023,0.8612685203552246,0.0015435691132928693,1744060569.1174047,0.8612685203552246,0.0,1744060569.117407,0.8612685203552246,56568542496.923805,1744060569.1174083,0.8612685203552246,0.0,1744060569.1174095,0.8612685203552246,-2.72867046800216e-14,1744060569.117411,0.8612685203552246,-0.0015575317190694303,1744060569.1174119,0.8612685203552246,-2.242845675301218e-24,1744060569.117413,0.8612685203552246,10,1744060569.1174145,0.8612685203552246,0.0,1744060569.1174154,0.8612685203552246,-22627416989.969524,1744060569.1174164,0.8612685203552246,0.0,1744060569.1174178,0.8612685203552246,28284271247.461903
+1744060569.1370935,0.8812718391418457,-0.0021229806224089573,1744060569.1370957,0.8812718391418457,0.0015435691132928693,1744060569.1370978,0.8812718391418457,0.0,1744060569.1371,0.8812718391418457,56568542496.923805,1744060569.1371014,0.8812718391418457,0.0,1744060569.1371028,0.8812718391418457,-2.72867046800216e-14,1744060569.137104,0.8812718391418457,-0.0015575317190694303,1744060569.1371055,0.8812718391418457,-2.242845675301218e-24,1744060569.1371067,0.8812718391418457,10,1744060569.1371078,0.8812718391418457,0.0,1744060569.137109,0.8812718391418457,-22627416989.969524,1744060569.1371102,0.8812718391418457,0.0,1744060569.1371117,0.8812718391418457,28284271247.461903
+1744060569.1573813,0.9012737274169922,-0.0021229806224089573,1744060569.1573832,0.9012737274169922,0.0015435691132928693,1744060569.1573856,0.9012737274169922,0.0,1744060569.1573877,0.9012737274169922,56568542496.923805,1744060569.1573887,0.9012737274169922,0.0,1744060569.15739,0.9012737274169922,-2.72867046800216e-14,1744060569.1573913,0.9012737274169922,-0.0015575317190694303,1744060569.1573927,0.9012737274169922,-2.242845675301218e-24,1744060569.157394,0.9012737274169922,10,1744060569.157395,0.9012737274169922,0.0,1744060569.1573963,0.9012737274169922,-22627416989.969524,1744060569.1573973,0.9012737274169922,0.0,1744060569.1573982,0.9012737274169922,28284271247.461903
+1744060569.1769786,0.9212291240692139,-0.0021229806224089573,1744060569.176981,0.9212291240692139,0.0015435691132928693,1744060569.176983,0.9212291240692139,0.0,1744060569.1769853,0.9212291240692139,56568542496.923805,1744060569.1769865,0.9212291240692139,0.0,1744060569.1769876,0.9212291240692139,-2.72867046800216e-14,1744060569.1769888,0.9212291240692139,-0.0015575317190694303,1744060569.17699,0.9212291240692139,-2.242845675301218e-24,1744060569.1769912,0.9212291240692139,10,1744060569.1769927,0.9212291240692139,0.0,1744060569.1769938,0.9212291240692139,-22627416989.969524,1744060569.1769948,0.9212291240692139,0.0,1744060569.1769958,0.9212291240692139,28284271247.461903
+1744060569.1974573,0.9415156841278076,-0.0021229806224089573,1744060569.1974602,0.9415156841278076,0.0015435691132928693,1744060569.197463,0.9415156841278076,0.0,1744060569.1974654,0.9415156841278076,56568542496.923805,1744060569.1974666,0.9415156841278076,0.0,1744060569.197468,0.9415156841278076,-2.72867046800216e-14,1744060569.19747,0.9415156841278076,-0.0015575317190694303,1744060569.1974711,0.9415156841278076,-2.242845675301218e-24,1744060569.197473,0.9415156841278076,10,1744060569.1974742,0.9415156841278076,0.0,1744060569.1974754,0.9415156841278076,-22627416989.969524,1744060569.1974769,0.9415156841278076,0.0,1744060569.1974778,0.9415156841278076,28284271247.461903
+1744060569.2173362,0.9612724781036377,-0.0021229806224089573,1744060569.2173414,0.9612724781036377,0.0015435691132928693,1744060569.2173467,0.9612724781036377,0.0,1744060569.217351,0.9612724781036377,56568542496.923805,1744060569.217353,0.9612724781036377,0.0,1744060569.217356,0.9612724781036377,-2.72867046800216e-14,1744060569.2173588,0.9612724781036377,-0.0015575317190694303,1744060569.2173624,0.9612724781036377,-2.242845675301218e-24,1744060569.2173657,0.9612724781036377,10,1744060569.217369,0.9612724781036377,0.0,1744060569.2173712,0.9612724781036377,-22627416989.969524,1744060569.2173738,0.9612724781036377,0.0,1744060569.2173772,0.9612724781036377,28284271247.461903
+1744060569.2370143,0.9812390804290771,-0.0021229806224089573,1744060569.2370167,0.9812390804290771,0.0015435691132928693,1744060569.2370188,0.9812390804290771,0.0,1744060569.237021,0.9812390804290771,56568542496.923805,1744060569.2370222,0.9812390804290771,0.0,1744060569.237023,0.9812390804290771,-2.72867046800216e-14,1744060569.2370248,0.9812390804290771,-0.0015575317190694303,1744060569.2370257,0.9812390804290771,-2.242845675301218e-24,1744060569.2370272,0.9812390804290771,10,1744060569.2370284,0.9812390804290771,0.0,1744060569.2370293,0.9812390804290771,-22627416989.969524,1744060569.2370307,0.9812390804290771,0.0,1744060569.237032,0.9812390804290771,28284271247.461903
+1744060569.2577696,1.0012931823730469,-0.006359533726547856,1744060569.2577748,1.0012931823730469,0.0017849822780012493,1744060569.257779,1.0012931823730469,0.0,1744060569.2577827,1.0012931823730469,56568542496.923805,1744060569.2577848,1.0012931823730469,0.0,1744060569.2577882,1.0012931823730469,-3.15543268256932e-14,1744060569.2577906,1.0012931823730469,-0.0018087465124678613,1744060569.2577927,1.0012931823730469,-2.6045949777689613e-24,1744060569.2577956,1.0012931823730469,10,1744060569.2577975,1.0012931823730469,0.0,1744060569.2577999,1.0012931823730469,-22627416989.969524,1744060569.2578025,1.0012931823730469,0.0,1744060569.257805,1.0012931823730469,28284271247.461903
+1744060569.2771535,1.021268606185913,-0.006359533726547856,1744060569.2771559,1.021268606185913,0.0017849822780012493,1744060569.2771587,1.021268606185913,0.0,1744060569.2771611,1.021268606185913,56568542496.923805,1744060569.2771626,1.021268606185913,0.0,1744060569.277164,1.021268606185913,-3.15543268256932e-14,1744060569.2771657,1.021268606185913,-0.0018087465124678613,1744060569.2771668,1.021268606185913,-2.6045949777689613e-24,1744060569.277168,1.021268606185913,10,1744060569.2771695,1.021268606185913,0.0,1744060569.2771707,1.021268606185913,-22627416989.969524,1744060569.2771716,1.021268606185913,0.0,1744060569.277173,1.021268606185913,28284271247.461903
+1744060569.2970736,1.0412695407867432,-0.006359533726547856,1744060569.297076,1.0412695407867432,0.0017849822780012493,1744060569.2970781,1.0412695407867432,0.0,1744060569.2970803,1.0412695407867432,56568542496.923805,1744060569.2970817,1.0412695407867432,0.0,1744060569.297083,1.0412695407867432,-3.15543268256932e-14,1744060569.297084,1.0412695407867432,-0.0018087465124678613,1744060569.2970855,1.0412695407867432,-2.6045949777689613e-24,1744060569.2970867,1.0412695407867432,10,1744060569.297088,1.0412695407867432,0.0,1744060569.297089,1.0412695407867432,-22627416989.969524,1744060569.2970903,1.0412695407867432,0.0,1744060569.2970912,1.0412695407867432,28284271247.461903
+1744060569.317104,1.061269760131836,-0.006359533726547856,1744060569.317106,1.061269760131836,0.0017849822780012493,1744060569.3171082,1.061269760131836,0.0,1744060569.3171108,1.061269760131836,56568542496.923805,1744060569.3171117,1.061269760131836,0.0,1744060569.3171134,1.061269760131836,-3.15543268256932e-14,1744060569.3171144,1.061269760131836,-0.0018087465124678613,1744060569.3171155,1.061269760131836,-2.6045949777689613e-24,1744060569.317117,1.061269760131836,10,1744060569.317118,1.061269760131836,0.0,1744060569.317119,1.061269760131836,-22627416989.969524,1744060569.3171203,1.061269760131836,0.0,1744060569.3171213,1.061269760131836,28284271247.461903
+1744060569.3371575,1.0812749862670898,-0.006359533726547856,1744060569.3371599,1.0812749862670898,0.0017849822780012493,1744060569.3371623,1.0812749862670898,0.0,1744060569.3371646,1.0812749862670898,56568542496.923805,1744060569.3371656,1.0812749862670898,0.0,1744060569.337167,1.0812749862670898,-3.15543268256932e-14,1744060569.3371685,1.0812749862670898,-0.0018087465124678613,1744060569.3371694,1.0812749862670898,-2.6045949777689613e-24,1744060569.3371706,1.0812749862670898,10,1744060569.337172,1.0812749862670898,0.0,1744060569.337173,1.0812749862670898,-22627416989.969524,1744060569.337174,1.0812749862670898,0.0,1744060569.3371751,1.0812749862670898,28284271247.461903
+1744060569.3576303,1.1012749671936035,-0.006359533726547856,1744060569.3576324,1.1012749671936035,0.0017849822780012493,1744060569.357635,1.1012749671936035,0.0,1744060569.357638,1.1012749671936035,56568542496.923805,1744060569.3576388,1.1012749671936035,0.0,1744060569.3576405,1.1012749671936035,-3.15543268256932e-14,1744060569.357642,1.1012749671936035,-0.0018087465124678613,1744060569.3576434,1.1012749671936035,-2.6045949777689613e-24,1744060569.3576446,1.1012749671936035,10,1744060569.3576458,1.1012749671936035,0.0,1744060569.357647,1.1012749671936035,-22627416989.969524,1744060569.3576481,1.1012749671936035,0.0,1744060569.3576493,1.1012749671936035,28284271247.461903
+1744060569.377112,1.1212666034698486,-0.006359533726547856,1744060569.3771138,1.1212666034698486,0.0017849822780012493,1744060569.3771164,1.1212666034698486,0.0,1744060569.3771183,1.1212666034698486,56568542496.923805,1744060569.3771198,1.1212666034698486,0.0,1744060569.377121,1.1212666034698486,-3.15543268256932e-14,1744060569.3771224,1.1212666034698486,-0.0018087465124678613,1744060569.3771234,1.1212666034698486,-2.6045949777689613e-24,1744060569.3771245,1.1212666034698486,10,1744060569.377126,1.1212666034698486,0.0,1744060569.377127,1.1212666034698486,-22627416989.969524,1744060569.377128,1.1212666034698486,0.0,1744060569.3771293,1.1212666034698486,28284271247.461903
+1744060569.3970108,1.1412372589111328,-0.006359533726547856,1744060569.3970127,1.1412372589111328,0.0017849822780012493,1744060569.397015,1.1412372589111328,0.0,1744060569.3970172,1.1412372589111328,56568542496.923805,1744060569.3970184,1.1412372589111328,0.0,1744060569.3970199,1.1412372589111328,-3.15543268256932e-14,1744060569.3970213,1.1412372589111328,-0.0018087465124678613,1744060569.3970225,1.1412372589111328,-2.6045949777689613e-24,1744060569.3970237,1.1412372589111328,10,1744060569.397025,1.1412372589111328,0.0,1744060569.397026,1.1412372589111328,-22627416989.969524,1744060569.397027,1.1412372589111328,0.0,1744060569.3970287,1.1412372589111328,28284271247.461903
+1744060569.417084,1.1612434387207031,-0.006359533726547856,1744060569.4170861,1.1612434387207031,0.0017849822780012493,1744060569.417089,1.1612434387207031,0.0,1744060569.4170914,1.1612434387207031,56568542496.923805,1744060569.4170926,1.1612434387207031,0.0,1744060569.417094,1.1612434387207031,-3.15543268256932e-14,1744060569.4170954,1.1612434387207031,-0.0018087465124678613,1744060569.4170966,1.1612434387207031,-2.6045949777689613e-24,1744060569.4170983,1.1612434387207031,10,1744060569.4170992,1.1612434387207031,0.0,1744060569.417101,1.1612434387207031,-22627416989.969524,1744060569.417102,1.1612434387207031,0.0,1744060569.4171033,1.1612434387207031,28284271247.461903
+1744060569.4370852,1.1812384128570557,-0.006359533726547856,1744060569.4370875,1.1812384128570557,0.0017849822780012493,1744060569.4370902,1.1812384128570557,0.0,1744060569.4370923,1.1812384128570557,56568542496.923805,1744060569.4370933,1.1812384128570557,0.0,1744060569.437095,1.1812384128570557,-3.15543268256932e-14,1744060569.437096,1.1812384128570557,-0.0018087465124678613,1744060569.4370975,1.1812384128570557,-2.6045949777689613e-24,1744060569.4370987,1.1812384128570557,10,1744060569.4371002,1.1812384128570557,0.0,1744060569.4371014,1.1812384128570557,-22627416989.969524,1744060569.4371026,1.1812384128570557,0.0,1744060569.4371035,1.1812384128570557,28284271247.461903
+1744060569.457623,1.2012526988983154,-0.006359533726547856,1744060569.4576263,1.2012526988983154,0.0017849822780012493,1744060569.4576294,1.2012526988983154,0.0,1744060569.4576335,1.2012526988983154,56568542496.923805,1744060569.4576356,1.2012526988983154,0.0,1744060569.457638,1.2012526988983154,-3.15543268256932e-14,1744060569.457641,1.2012526988983154,-0.0018087465124678613,1744060569.457643,1.2012526988983154,-2.6045949777689613e-24,1744060569.4576454,1.2012526988983154,10,1744060569.457647,1.2012526988983154,0.0,1744060569.4576495,1.2012526988983154,-22627416989.969524,1744060569.4576511,1.2012526988983154,0.0,1744060569.4576533,1.2012526988983154,28284271247.461903
+1744060569.476971,1.2213096618652344,-0.006359533726547856,1744060569.476973,1.2213096618652344,0.0017849822780012493,1744060569.4769754,1.2213096618652344,0.0,1744060569.4769773,1.2213096618652344,56568542496.923805,1744060569.4769788,1.2213096618652344,0.0,1744060569.47698,1.2213096618652344,-3.15543268256932e-14,1744060569.476981,1.2213096618652344,-0.0018087465124678613,1744060569.4769824,1.2213096618652344,-2.6045949777689613e-24,1744060569.4769835,1.2213096618652344,10,1744060569.4769845,1.2213096618652344,0.0,1744060569.4769857,1.2213096618652344,-22627416989.969524,1744060569.4769871,1.2213096618652344,0.0,1744060569.476988,1.2213096618652344,28284271247.461903
+1744060569.4980724,1.2412991523742676,-0.006359533726547856,1744060569.4980748,1.2412991523742676,0.0017849822780012493,1744060569.4980776,1.2412991523742676,0.0,1744060569.4980803,1.2412991523742676,56568542496.923805,1744060569.4980817,1.2412991523742676,0.0,1744060569.4980984,1.2412991523742676,-3.15543268256932e-14,1744060569.498101,1.2412991523742676,-0.0018087465124678613,1744060569.4981031,1.2412991523742676,-2.6045949777689613e-24,1744060569.4981053,1.2412991523742676,10,1744060569.4981077,1.2412991523742676,0.0,1744060569.49811,1.2412991523742676,-22627416989.969524,1744060569.4981122,1.2412991523742676,0.0,1744060569.4981146,1.2412991523742676,28284271247.461903
+1744060569.5170455,1.2612364292144775,-0.006359533726547856,1744060569.517048,1.2612364292144775,0.0017849822780012493,1744060569.51705,1.2612364292144775,0.0,1744060569.517053,1.2612364292144775,56568542496.923805,1744060569.5170546,1.2612364292144775,0.0,1744060569.5170557,1.2612364292144775,-3.15543268256932e-14,1744060569.517057,1.2612364292144775,-0.0018087465124678613,1744060569.5170584,1.2612364292144775,-2.6045949777689613e-24,1744060569.51706,1.2612364292144775,10,1744060569.5170624,1.2612364292144775,0.0,1744060569.517064,1.2612364292144775,-22627416989.969524,1744060569.5170665,1.2612364292144775,0.0,1744060569.5170689,1.2612364292144775,28284271247.461903
+1744060569.5370247,1.2812414169311523,-0.006359533726547856,1744060569.5370271,1.2812414169311523,0.0017849822780012493,1744060569.5370293,1.2812414169311523,0.0,1744060569.537032,1.2812414169311523,56568542496.923805,1744060569.5370333,1.2812414169311523,0.0,1744060569.5370345,1.2812414169311523,-3.15543268256932e-14,1744060569.5370357,1.2812414169311523,-0.0018087465124678613,1744060569.5370371,1.2812414169311523,-2.6045949777689613e-24,1744060569.5370383,1.2812414169311523,10,1744060569.5370395,1.2812414169311523,0.0,1744060569.5370407,1.2812414169311523,-22627416989.969524,1744060569.5370421,1.2812414169311523,0.0,1744060569.5370436,1.2812414169311523,28284271247.461903
+1744060569.5573049,1.3012416362762451,-0.006359533726547856,1744060569.5573068,1.3012416362762451,0.0017849822780012493,1744060569.557309,1.3012416362762451,0.0,1744060569.5573113,1.3012416362762451,56568542496.923805,1744060569.5573123,1.3012416362762451,0.0,1744060569.5573134,1.3012416362762451,-3.15543268256932e-14,1744060569.5573149,1.3012416362762451,-0.0018087465124678613,1744060569.5573158,1.3012416362762451,-2.6045949777689613e-24,1744060569.557317,1.3012416362762451,10,1744060569.5573182,1.3012416362762451,0.0,1744060569.5573192,1.3012416362762451,-22627416989.969524,1744060569.5573204,1.3012416362762451,0.0,1744060569.5573215,1.3012416362762451,28284271247.461903
+1744060569.5772295,1.3212366104125977,-0.006359533726547856,1744060569.5772316,1.3212366104125977,0.0017849822780012493,1744060569.577234,1.3212366104125977,0.0,1744060569.5772362,1.3212366104125977,56568542496.923805,1744060569.5772371,1.3212366104125977,0.0,1744060569.5772386,1.3212366104125977,-3.15543268256932e-14,1744060569.5772398,1.3212366104125977,-0.0018087465124678613,1744060569.5772412,1.3212366104125977,-2.6045949777689613e-24,1744060569.5772421,1.3212366104125977,10,1744060569.5772433,1.3212366104125977,0.0,1744060569.5772445,1.3212366104125977,-22627416989.969524,1744060569.5772455,1.3212366104125977,0.0,1744060569.5772464,1.3212366104125977,28284271247.461903
+1744060569.597596,1.3412971496582031,-0.006359533726547856,1744060569.5975983,1.3412971496582031,0.0017849822780012493,1744060569.5976005,1.3412971496582031,0.0,1744060569.597603,1.3412971496582031,56568542496.923805,1744060569.5976043,1.3412971496582031,0.0,1744060569.5976057,1.3412971496582031,-3.15543268256932e-14,1744060569.597607,1.3412971496582031,-0.0018087465124678613,1744060569.5976079,1.3412971496582031,-2.6045949777689613e-24,1744060569.5976093,1.3412971496582031,10,1744060569.5976102,1.3412971496582031,0.0,1744060569.5976112,1.3412971496582031,-22627416989.969524,1744060569.5976126,1.3412971496582031,0.0,1744060569.5976136,1.3412971496582031,28284271247.461903
+1744060569.616993,1.3612697124481201,-0.006359533726547856,1744060569.616995,1.3612697124481201,0.0017849822780012493,1744060569.6169975,1.3612697124481201,0.0,1744060569.6169996,1.3612697124481201,56568542496.923805,1744060569.6170008,1.3612697124481201,0.0,1744060569.617002,1.3612697124481201,-3.15543268256932e-14,1744060569.6170032,1.3612697124481201,-0.0018087465124678613,1744060569.6170046,1.3612697124481201,-2.6045949777689613e-24,1744060569.6170058,1.3612697124481201,10,1744060569.6170068,1.3612697124481201,0.0,1744060569.6170082,1.3612697124481201,-22627416989.969524,1744060569.6170092,1.3612697124481201,0.0,1744060569.61701,1.3612697124481201,28284271247.461903
+1744060569.6372013,1.3812386989593506,-0.006359533726547856,1744060569.6372037,1.3812386989593506,0.0017849822780012493,1744060569.6372063,1.3812386989593506,0.0,1744060569.6372094,1.3812386989593506,56568542496.923805,1744060569.6372108,1.3812386989593506,0.0,1744060569.6372128,1.3812386989593506,-3.15543268256932e-14,1744060569.6372142,1.3812386989593506,-0.0018087465124678613,1744060569.6372159,1.3812386989593506,-2.6045949777689613e-24,1744060569.6372175,1.3812386989593506,10,1744060569.6372194,1.3812386989593506,0.0,1744060569.6372206,1.3812386989593506,-22627416989.969524,1744060569.6372216,1.3812386989593506,0.0,1744060569.6372232,1.3812386989593506,28284271247.461903
+1744060569.6574938,1.4012949466705322,-0.006359533726547856,1744060569.6574957,1.4012949466705322,0.0017849822780012493,1744060569.657498,1.4012949466705322,0.0,1744060569.6575003,1.4012949466705322,56568542496.923805,1744060569.6575012,1.4012949466705322,0.0,1744060569.6575024,1.4012949466705322,-3.15543268256932e-14,1744060569.6575038,1.4012949466705322,-0.0018087465124678613,1744060569.657505,1.4012949466705322,-2.6045949777689613e-24,1744060569.657506,1.4012949466705322,10,1744060569.6575077,1.4012949466705322,0.0,1744060569.6575086,1.4012949466705322,-22627416989.969524,1744060569.6575096,1.4012949466705322,0.0,1744060569.6575108,1.4012949466705322,28284271247.461903
+1744060569.6770086,1.4212336540222168,-0.006359533726547856,1744060569.6770108,1.4212336540222168,0.0017849822780012493,1744060569.6770127,1.4212336540222168,0.0,1744060569.677015,1.4212336540222168,56568542496.923805,1744060569.677016,1.4212336540222168,0.0,1744060569.6770175,1.4212336540222168,-3.15543268256932e-14,1744060569.6770186,1.4212336540222168,-0.0018087465124678613,1744060569.6770198,1.4212336540222168,-2.6045949777689613e-24,1744060569.6770213,1.4212336540222168,10,1744060569.6770225,1.4212336540222168,0.0,1744060569.6770234,1.4212336540222168,-22627416989.969524,1744060569.6770248,1.4212336540222168,0.0,1744060569.6770258,1.4212336540222168,28284271247.461903
+1744060569.6978598,1.4412345886230469,-0.006359533726547856,1744060569.6978633,1.4412345886230469,0.0017849822780012493,1744060569.697867,1.4412345886230469,0.0,1744060569.6978705,1.4412345886230469,56568542496.923805,1744060569.6978726,1.4412345886230469,0.0,1744060569.6978745,1.4412345886230469,-3.15543268256932e-14,1744060569.6978762,1.4412345886230469,-0.0018087465124678613,1744060569.6978781,1.4412345886230469,-2.6045949777689613e-24,1744060569.6978796,1.4412345886230469,10,1744060569.697881,1.4412345886230469,0.0,1744060569.697883,1.4412345886230469,-22627416989.969524,1744060569.697885,1.4412345886230469,0.0,1744060569.6978865,1.4412345886230469,28284271247.461903
+1744060569.7169127,1.4612298011779785,-0.006359533726547856,1744060569.7169147,1.4612298011779785,0.0017849822780012493,1744060569.7169187,1.4612298011779785,0.0,1744060569.7169213,1.4612298011779785,56568542496.923805,1744060569.7169223,1.4612298011779785,0.0,1744060569.7169237,1.4612298011779785,-3.15543268256932e-14,1744060569.7169251,1.4612298011779785,-0.0018087465124678613,1744060569.716926,1.4612298011779785,-2.6045949777689613e-24,1744060569.7169275,1.4612298011779785,10,1744060569.7169285,1.4612298011779785,0.0,1744060569.7169292,1.4612298011779785,-22627416989.969524,1744060569.7169304,1.4612298011779785,0.0,1744060569.7169313,1.4612298011779785,28284271247.461903
+1744060569.737072,1.4812431335449219,-0.006359533726547856,1744060569.737074,1.4812431335449219,0.0017849822780012493,1744060569.7370763,1.4812431335449219,0.0,1744060569.737078,1.4812431335449219,56568542496.923805,1744060569.7370791,1.4812431335449219,0.0,1744060569.7370803,1.4812431335449219,-3.15543268256932e-14,1744060569.7370815,1.4812431335449219,-0.0018087465124678613,1744060569.7370832,1.4812431335449219,-2.6045949777689613e-24,1744060569.7370846,1.4812431335449219,10,1744060569.7370856,1.4812431335449219,0.0,1744060569.7370868,1.4812431335449219,-22627416989.969524,1744060569.7370877,1.4812431335449219,0.0,1744060569.737089,1.4812431335449219,28284271247.461903
+1744060569.7573762,1.5012695789337158,-0.015461857256702315,1744060569.757378,1.5012695789337158,0.0018242832373857308,1744060569.75738,1.5012695789337158,0.0,1744060569.757382,1.5012695789337158,56568542496.923805,1744060569.757383,1.5012695789337158,0.0,1744060569.7573843,1.5012695789337158,-3.2249076197860966e-14,1744060569.7573855,1.5012695789337158,-0.0018087465124681523,1744060569.7573864,1.5012695789337158,-2.604594977768542e-24,1744060569.7573879,1.5012695789337158,10,1744060569.7573888,1.5012695789337158,0.0,1744060569.7573895,1.5012695789337158,-22627416989.969524,1744060569.7573907,1.5012695789337158,0.0,1744060569.7573917,1.5012695789337158,28284271247.461903
+1744060569.777256,1.521261215209961,-0.015461857256702315,1744060569.777258,1.521261215209961,0.0018242832373857308,1744060569.7772603,1.521261215209961,0.0,1744060569.7772624,1.521261215209961,56568542496.923805,1744060569.7772634,1.521261215209961,0.0,1744060569.7772646,1.521261215209961,-3.2249076197860966e-14,1744060569.7772655,1.521261215209961,-0.0018087465124681523,1744060569.777267,1.521261215209961,-2.604594977768542e-24,1744060569.777268,1.521261215209961,10,1744060569.777269,1.521261215209961,0.0,1744060569.7772698,1.521261215209961,-22627416989.969524,1744060569.7772708,1.521261215209961,0.0,1744060569.7772717,1.521261215209961,28284271247.461903
+1744060569.797072,1.5412664413452148,-0.015461857256702315,1744060569.797074,1.5412664413452148,0.0018242832373857308,1744060569.7970765,1.5412664413452148,0.0,1744060569.797079,1.5412664413452148,56568542496.923805,1744060569.797081,1.5412664413452148,0.0,1744060569.7970827,1.5412664413452148,-3.2249076197860966e-14,1744060569.797084,1.5412664413452148,-0.0018087465124681523,1744060569.7970858,1.5412664413452148,-2.604594977768542e-24,1744060569.797087,1.5412664413452148,10,1744060569.7970881,1.5412664413452148,0.0,1744060569.7970893,1.5412664413452148,-22627416989.969524,1744060569.7970903,1.5412664413452148,0.0,1744060569.7970912,1.5412664413452148,28284271247.461903
+1744060569.817156,1.5612401962280273,-0.015461857256702315,1744060569.817158,1.5612401962280273,0.0018242832373857308,1744060569.8171601,1.5612401962280273,0.0,1744060569.8171623,1.5612401962280273,56568542496.923805,1744060569.8171635,1.5612401962280273,0.0,1744060569.8171647,1.5612401962280273,-3.2249076197860966e-14,1744060569.8171659,1.5612401962280273,-0.0018087465124681523,1744060569.817167,1.5612401962280273,-2.604594977768542e-24,1744060569.8171685,1.5612401962280273,10,1744060569.8171692,1.5612401962280273,0.0,1744060569.8171701,1.5612401962280273,-22627416989.969524,1744060569.817171,1.5612401962280273,0.0,1744060569.8171723,1.5612401962280273,28284271247.461903
+1744060569.8372097,1.5812656879425049,-0.015461857256702315,1744060569.837213,1.5812656879425049,0.0018242832373857308,1744060569.8372166,1.5812656879425049,0.0,1744060569.83722,1.5812656879425049,56568542496.923805,1744060569.8372216,1.5812656879425049,0.0,1744060569.8372235,1.5812656879425049,-3.2249076197860966e-14,1744060569.8372252,1.5812656879425049,-0.0018087465124681523,1744060569.8372269,1.5812656879425049,-2.604594977768542e-24,1744060569.8372285,1.5812656879425049,10,1744060569.8372307,1.5812656879425049,0.0,1744060569.837232,1.5812656879425049,-22627416989.969524,1744060569.8372338,1.5812656879425049,0.0,1744060569.8372355,1.5812656879425049,28284271247.461903
+1744060569.8576002,1.6013023853302002,-0.015461857256702315,1744060569.8576021,1.6013023853302002,0.0018242832373857308,1744060569.857604,1.6013023853302002,0.0,1744060569.8576062,1.6013023853302002,56568542496.923805,1744060569.8576071,1.6013023853302002,0.0,1744060569.857608,1.6013023853302002,-3.2249076197860966e-14,1744060569.8576095,1.6013023853302002,-0.0018087465124681523,1744060569.8576105,1.6013023853302002,-2.604594977768542e-24,1744060569.8576114,1.6013023853302002,10,1744060569.8576128,1.6013023853302002,0.0,1744060569.8576138,1.6013023853302002,-22627416989.969524,1744060569.8576148,1.6013023853302002,0.0,1744060569.8576157,1.6013023853302002,28284271247.461903
+1744060569.876961,1.6212313175201416,-0.015461857256702315,1744060569.876963,1.6212313175201416,0.0018242832373857308,1744060569.8769648,1.6212313175201416,0.0,1744060569.8769672,1.6212313175201416,56568542496.923805,1744060569.8769681,1.6212313175201416,0.0,1744060569.876969,1.6212313175201416,-3.2249076197860966e-14,1744060569.8769705,1.6212313175201416,-0.0018087465124681523,1744060569.876972,1.6212313175201416,-2.604594977768542e-24,1744060569.8769732,1.6212313175201416,10,1744060569.876974,1.6212313175201416,0.0,1744060569.876975,1.6212313175201416,-22627416989.969524,1744060569.8769758,1.6212313175201416,0.0,1744060569.876977,1.6212313175201416,28284271247.461903
+1744060569.8972156,1.641270399093628,-0.015461857256702315,1744060569.8972173,1.641270399093628,0.0018242832373857308,1744060569.8972197,1.641270399093628,0.0,1744060569.8972216,1.641270399093628,56568542496.923805,1744060569.8972228,1.641270399093628,0.0,1744060569.897224,1.641270399093628,-3.2249076197860966e-14,1744060569.897225,1.641270399093628,-0.0018087465124681523,1744060569.897226,1.641270399093628,-2.604594977768542e-24,1744060569.8972273,1.641270399093628,10,1744060569.897228,1.641270399093628,0.0,1744060569.897229,1.641270399093628,-22627416989.969524,1744060569.8972304,1.641270399093628,0.0,1744060569.8972313,1.641270399093628,28284271247.461903
+1744060569.9173725,1.6613376140594482,-0.015461857256702315,1744060569.9173744,1.6613376140594482,0.0018242832373857308,1744060569.9173765,1.6613376140594482,0.0,1744060569.9173787,1.6613376140594482,56568542496.923805,1744060569.9173796,1.6613376140594482,0.0,1744060569.9173808,1.6613376140594482,-3.2249076197860966e-14,1744060569.9173822,1.6613376140594482,-0.0018087465124681523,1744060569.9173832,1.6613376140594482,-2.604594977768542e-24,1744060569.9173844,1.6613376140594482,10,1744060569.9173856,1.6613376140594482,0.0,1744060569.9173865,1.6613376140594482,-22627416989.969524,1744060569.9173875,1.6613376140594482,0.0,1744060569.9173884,1.6613376140594482,28284271247.461903
+1744060569.9372766,1.6812443733215332,-0.015461857256702315,1744060569.93728,1.6812443733215332,0.0018242832373857308,1744060569.9372835,1.6812443733215332,0.0,1744060569.9372869,1.6812443733215332,56568542496.923805,1744060569.9372885,1.6812443733215332,0.0,1744060569.9372904,1.6812443733215332,-3.2249076197860966e-14,1744060569.9372928,1.6812443733215332,-0.0018087465124681523,1744060569.9372945,1.6812443733215332,-2.604594977768542e-24,1744060569.9372966,1.6812443733215332,10,1744060569.9372985,1.6812443733215332,0.0,1744060569.9373004,1.6812443733215332,-22627416989.969524,1744060569.9373026,1.6812443733215332,0.0,1744060569.937304,1.6812443733215332,28284271247.461903
+1744060569.9573796,1.701249599456787,-0.015461857256702315,1744060569.9573815,1.701249599456787,0.0018242832373857308,1744060569.9573834,1.701249599456787,0.0,1744060569.9573855,1.701249599456787,56568542496.923805,1744060569.9573865,1.701249599456787,0.0,1744060569.9573877,1.701249599456787,-3.2249076197860966e-14,1744060569.957389,1.701249599456787,-0.0018087465124681523,1744060569.95739,1.701249599456787,-2.604594977768542e-24,1744060569.957391,1.701249599456787,10,1744060569.9573922,1.701249599456787,0.0,1744060569.9573932,1.701249599456787,-22627416989.969524,1744060569.9573941,1.701249599456787,0.0,1744060569.9573953,1.701249599456787,28284271247.461903
+1744060569.9770896,1.7212402820587158,-0.015461857256702315,1744060569.977092,1.7212402820587158,0.0018242832373857308,1744060569.9770951,1.7212402820587158,0.0,1744060569.977098,1.7212402820587158,56568542496.923805,1744060569.9770994,1.7212402820587158,0.0,1744060569.9771013,1.7212402820587158,-3.2249076197860966e-14,1744060569.977103,1.7212402820587158,-0.0018087465124681523,1744060569.9771047,1.7212402820587158,-2.604594977768542e-24,1744060569.977106,1.7212402820587158,10,1744060569.9771075,1.7212402820587158,0.0,1744060569.9771087,1.7212402820587158,-22627416989.969524,1744060569.9771104,1.7212402820587158,0.0,1744060569.9771118,1.7212402820587158,28284271247.461903
+1744060569.9971101,1.741241455078125,-0.015461857256702315,1744060569.9971118,1.741241455078125,0.0018242832373857308,1744060569.9971142,1.741241455078125,0.0,1744060569.9971163,1.741241455078125,56568542496.923805,1744060569.9971175,1.741241455078125,0.0,1744060569.9971187,1.741241455078125,-3.2249076197860966e-14,1744060569.99712,1.741241455078125,-0.0018087465124681523,1744060569.9971213,1.741241455078125,-2.604594977768542e-24,1744060569.9971225,1.741241455078125,10,1744060569.9971235,1.741241455078125,0.0,1744060569.9971247,1.741241455078125,-22627416989.969524,1744060569.997126,1.741241455078125,0.0,1744060569.997128,1.741241455078125,28284271247.461903
+1744060570.017254,1.7612457275390625,-0.015461857256702315,1744060570.0172572,1.7612457275390625,0.0018242832373857308,1744060570.0172596,1.7612457275390625,0.0,1744060570.0172617,1.7612457275390625,56568542496.923805,1744060570.0172637,1.7612457275390625,0.0,1744060570.0172653,1.7612457275390625,-3.2249076197860966e-14,1744060570.0172668,1.7612457275390625,-0.0018087465124681523,1744060570.017268,1.7612457275390625,-2.604594977768542e-24,1744060570.0172691,1.7612457275390625,10,1744060570.0172706,1.7612457275390625,0.0,1744060570.0172715,1.7612457275390625,-22627416989.969524,1744060570.017273,1.7612457275390625,0.0,1744060570.017274,1.7612457275390625,28284271247.461903
+1744060570.0369902,1.7812647819519043,-0.015461857256702315,1744060570.0369933,1.7812647819519043,0.0018242832373857308,1744060570.0369964,1.7812647819519043,0.0,1744060570.0370002,1.7812647819519043,56568542496.923805,1744060570.0370016,1.7812647819519043,0.0,1744060570.0370038,1.7812647819519043,-3.2249076197860966e-14,1744060570.0370057,1.7812647819519043,-0.0018087465124681523,1744060570.0370073,1.7812647819519043,-2.604594977768542e-24,1744060570.0370095,1.7812647819519043,10,1744060570.037011,1.7812647819519043,0.0,1744060570.0370128,1.7812647819519043,-22627416989.969524,1744060570.0370142,1.7812647819519043,0.0,1744060570.037016,1.7812647819519043,28284271247.461903
+1744060570.057716,1.8012628555297852,-0.015461857256702315,1744060570.0577188,1.8012628555297852,0.0018242832373857308,1744060570.0577223,1.8012628555297852,0.0,1744060570.057726,1.8012628555297852,56568542496.923805,1744060570.0577278,1.8012628555297852,0.0,1744060570.0577302,1.8012628555297852,-3.2249076197860966e-14,1744060570.0577326,1.8012628555297852,-0.0018087465124681523,1744060570.0577347,1.8012628555297852,-2.604594977768542e-24,1744060570.0577369,1.8012628555297852,10,1744060570.057739,1.8012628555297852,0.0,1744060570.0577412,1.8012628555297852,-22627416989.969524,1744060570.057743,1.8012628555297852,0.0,1744060570.0577452,1.8012628555297852,28284271247.461903
+1744060570.077311,1.821265459060669,-0.015461857256702315,1744060570.0773132,1.821265459060669,0.0018242832373857308,1744060570.0773156,1.821265459060669,0.0,1744060570.077318,1.821265459060669,56568542496.923805,1744060570.077319,1.821265459060669,0.0,1744060570.0773199,1.821265459060669,-3.2249076197860966e-14,1744060570.0773213,1.821265459060669,-0.0018087465124681523,1744060570.0773225,1.821265459060669,-2.604594977768542e-24,1744060570.0773234,1.821265459060669,10,1744060570.0773246,1.821265459060669,0.0,1744060570.0773256,1.821265459060669,-22627416989.969524,1744060570.0773265,1.821265459060669,0.0,1744060570.077328,1.821265459060669,28284271247.461903
+1744060570.097166,1.841245174407959,-0.015461857256702315,1744060570.097168,1.841245174407959,0.0018242832373857308,1744060570.0971699,1.841245174407959,0.0,1744060570.097172,1.841245174407959,56568542496.923805,1744060570.097173,1.841245174407959,0.0,1744060570.0971742,1.841245174407959,-3.2249076197860966e-14,1744060570.0971756,1.841245174407959,-0.0018087465124681523,1744060570.0971766,1.841245174407959,-2.604594977768542e-24,1744060570.0971777,1.841245174407959,10,1744060570.0971792,1.841245174407959,0.0,1744060570.09718,1.841245174407959,-22627416989.969524,1744060570.0971808,1.841245174407959,0.0,1744060570.097182,1.841245174407959,28284271247.461903
+1744060570.1169379,1.8612618446350098,-0.015461857256702315,1744060570.116941,1.8612618446350098,0.0018242832373857308,1744060570.116944,1.8612618446350098,0.0,1744060570.116947,1.8612618446350098,56568542496.923805,1744060570.1169481,1.8612618446350098,0.0,1744060570.11695,1.8612618446350098,-3.2249076197860966e-14,1744060570.1169512,1.8612618446350098,-0.0018087465124681523,1744060570.1169527,1.8612618446350098,-2.604594977768542e-24,1744060570.116954,1.8612618446350098,10,1744060570.116955,1.8612618446350098,0.0,1744060570.1169627,1.8612618446350098,-22627416989.969524,1744060570.1169636,1.8612618446350098,0.0,1744060570.1169648,1.8612618446350098,28284271247.461903
+1744060570.1369712,1.881256103515625,-0.015461857256702315,1744060570.1369731,1.881256103515625,0.0018242832373857308,1744060570.1369753,1.881256103515625,0.0,1744060570.1369774,1.881256103515625,56568542496.923805,1744060570.1369784,1.881256103515625,0.0,1744060570.1369798,1.881256103515625,-3.2249076197860966e-14,1744060570.136981,1.881256103515625,-0.0018087465124681523,1744060570.1369822,1.881256103515625,-2.604594977768542e-24,1744060570.1369834,1.881256103515625,10,1744060570.1369848,1.881256103515625,0.0,1744060570.1369858,1.881256103515625,-22627416989.969524,1744060570.136987,1.881256103515625,0.0,1744060570.136988,1.881256103515625,28284271247.461903
+1744060570.157515,1.9013309478759766,-0.015461857256702315,1744060570.1575167,1.9013309478759766,0.0018242832373857308,1744060570.1575437,1.9013309478759766,0.0,1744060570.157547,1.9013309478759766,56568542496.923805,1744060570.1575484,1.9013309478759766,0.0,1744060570.1575506,1.9013309478759766,-3.2249076197860966e-14,1744060570.1575525,1.9013309478759766,-0.0018087465124681523,1744060570.1575541,1.9013309478759766,-2.604594977768542e-24,1744060570.1575563,1.9013309478759766,10,1744060570.157558,1.9013309478759766,0.0,1744060570.1575599,1.9013309478759766,-22627416989.969524,1744060570.1575615,1.9013309478759766,0.0,1744060570.1575637,1.9013309478759766,28284271247.461903
+1744060570.176968,1.9212322235107422,-0.015461857256702315,1744060570.1769702,1.9212322235107422,0.0018242832373857308,1744060570.1769726,1.9212322235107422,0.0,1744060570.1769745,1.9212322235107422,56568542496.923805,1744060570.1769757,1.9212322235107422,0.0,1744060570.176977,1.9212322235107422,-3.2249076197860966e-14,1744060570.1769779,1.9212322235107422,-0.0018087465124681523,1744060570.1769793,1.9212322235107422,-2.604594977768542e-24,1744060570.1769803,1.9212322235107422,10,1744060570.1769812,1.9212322235107422,0.0,1744060570.1769822,1.9212322235107422,-22627416989.969524,1744060570.176983,1.9212322235107422,0.0,1744060570.176984,1.9212322235107422,28284271247.461903
+1744060570.1971264,1.9412801265716553,-0.015461857256702315,1744060570.1971292,1.9412801265716553,0.0018242832373857308,1744060570.1971316,1.9412801265716553,0.0,1744060570.1971338,1.9412801265716553,56568542496.923805,1744060570.1971347,1.9412801265716553,0.0,1744060570.1971364,1.9412801265716553,-3.2249076197860966e-14,1744060570.1971378,1.9412801265716553,-0.0018087465124681523,1744060570.1971393,1.9412801265716553,-2.604594977768542e-24,1744060570.197141,1.9412801265716553,10,1744060570.1971424,1.9412801265716553,0.0,1744060570.197143,1.9412801265716553,-22627416989.969524,1744060570.1971443,1.9412801265716553,0.0,1744060570.197146,1.9412801265716553,28284271247.461903
+1744060570.2169948,1.9612696170806885,-0.015461857256702315,1744060570.216997,1.9612696170806885,0.0018242832373857308,1744060570.2170184,1.9612696170806885,0.0,1744060570.217021,1.9612696170806885,56568542496.923805,1744060570.217022,1.9612696170806885,0.0,1744060570.2170231,1.9612696170806885,-3.2249076197860966e-14,1744060570.2170246,1.9612696170806885,-0.0018087465124681523,1744060570.2170258,1.9612696170806885,-2.604594977768542e-24,1744060570.2170272,1.9612696170806885,10,1744060570.2170281,1.9612696170806885,0.0,1744060570.217029,1.9612696170806885,-22627416989.969524,1744060570.21703,1.9612696170806885,0.0,1744060570.2170312,1.9612696170806885,28284271247.461903
+1744060570.2373514,1.9812824726104736,-0.015461857256702315,1744060570.2373533,1.9812824726104736,0.0018242832373857308,1744060570.2373555,1.9812824726104736,0.0,1744060570.2373579,1.9812824726104736,56568542496.923805,1744060570.2373588,1.9812824726104736,0.0,1744060570.2373602,1.9812824726104736,-3.2249076197860966e-14,1744060570.2373614,1.9812824726104736,-0.0018087465124681523,1744060570.2373626,1.9812824726104736,-2.604594977768542e-24,1744060570.237364,1.9812824726104736,10,1744060570.2373652,1.9812824726104736,0.0,1744060570.2373664,1.9812824726104736,-22627416989.969524,1744060570.2373676,1.9812824726104736,0.0,1744060570.2373688,1.9812824726104736,28284271247.461903
+1744060570.2575445,2.0012519359588623,-0.02231415569330805,1744060570.2575462,2.0012519359588623,0.0026744851096756634,1744060570.2575483,2.0012519359588623,0.0,1744060570.2575502,2.0012519359588623,56568542496.923805,1744060570.2575514,2.0012519359588623,0.0,1744060570.2575526,2.0012519359588623,-4.7278663929162514e-14,1744060570.2575538,2.0012519359588623,-0.00266287681002288,1744060570.257555,2.0012519359588623,-3.834542606158778e-24,1744060570.257556,2.0012519359588623,10,1744060570.257557,2.0012519359588623,0.0,1744060570.257558,2.0012519359588623,-22627416989.969524,1744060570.257559,2.0012519359588623,0.0,1744060570.2575598,2.0012519359588623,28284271247.461903
+1744060570.2770176,2.0212628841400146,-0.02231415569330805,1744060570.2770195,2.0212628841400146,0.0026744851096756634,1744060570.2770216,2.0212628841400146,0.0,1744060570.277024,2.0212628841400146,56568542496.923805,1744060570.2770252,2.0212628841400146,0.0,1744060570.2770267,2.0212628841400146,-4.7278663929162514e-14,1744060570.2770278,2.0212628841400146,-0.00266287681002288,1744060570.277029,2.0212628841400146,-3.834542606158778e-24,1744060570.2770302,2.0212628841400146,10,1744060570.2770312,2.0212628841400146,0.0,1744060570.2770321,2.0212628841400146,-22627416989.969524,1744060570.2770333,2.0212628841400146,0.0,1744060570.2770343,2.0212628841400146,28284271247.461903
+1744060570.2970562,2.0412378311157227,-0.02231415569330805,1744060570.297058,2.0412378311157227,0.0026744851096756634,1744060570.2970603,2.0412378311157227,0.0,1744060570.2970624,2.0412378311157227,56568542496.923805,1744060570.2970634,2.0412378311157227,0.0,1744060570.2970648,2.0412378311157227,-4.7278663929162514e-14,1744060570.297066,2.0412378311157227,-0.00266287681002288,1744060570.2970672,2.0412378311157227,-3.834542606158778e-24,1744060570.2970686,2.0412378311157227,10,1744060570.2970695,2.0412378311157227,0.0,1744060570.2970705,2.0412378311157227,-22627416989.969524,1744060570.297086,2.0412378311157227,0.0,1744060570.2970872,2.0412378311157227,28284271247.461903
+1744060570.3169475,2.061234712600708,-0.02231415569330805,1744060570.3169491,2.061234712600708,0.0026744851096756634,1744060570.3169513,2.061234712600708,0.0,1744060570.3169534,2.061234712600708,56568542496.923805,1744060570.3169544,2.061234712600708,0.0,1744060570.3169556,2.061234712600708,-4.7278663929162514e-14,1744060570.316957,2.061234712600708,-0.00266287681002288,1744060570.316982,2.061234712600708,-3.834542606158778e-24,1744060570.316983,2.061234712600708,10,1744060570.3169844,2.061234712600708,0.0,1744060570.3169854,2.061234712600708,-22627416989.969524,1744060570.3169863,2.061234712600708,0.0,1744060570.3169873,2.061234712600708,28284271247.461903
+1744060570.3369985,2.0812621116638184,-0.02231415569330805,1744060570.3370004,2.0812621116638184,0.0026744851096756634,1744060570.3370028,2.0812621116638184,0.0,1744060570.3370051,2.0812621116638184,56568542496.923805,1744060570.3370059,2.0812621116638184,0.0,1744060570.337007,2.0812621116638184,-4.7278663929162514e-14,1744060570.3370085,2.0812621116638184,-0.00266287681002288,1744060570.3370097,2.0812621116638184,-3.834542606158778e-24,1744060570.3370109,2.0812621116638184,10,1744060570.337012,2.0812621116638184,0.0,1744060570.337013,2.0812621116638184,-22627416989.969524,1744060570.337014,2.0812621116638184,0.0,1744060570.3370152,2.0812621116638184,28284271247.461903
+1744060570.3577442,2.1012558937072754,-0.02231415569330805,1744060570.3577464,2.1012558937072754,0.0026744851096756634,1744060570.3577487,2.1012558937072754,0.0,1744060570.3577514,2.1012558937072754,56568542496.923805,1744060570.3577523,2.1012558937072754,0.0,1744060570.3577535,2.1012558937072754,-4.7278663929162514e-14,1744060570.357755,2.1012558937072754,-0.00266287681002288,1744060570.357756,2.1012558937072754,-3.834542606158778e-24,1744060570.3577578,2.1012558937072754,10,1744060570.357759,2.1012558937072754,0.0,1744060570.3577602,2.1012558937072754,-22627416989.969524,1744060570.3577619,2.1012558937072754,0.0,1744060570.3577633,2.1012558937072754,28284271247.461903
+1744060570.3771384,2.121258497238159,-0.02231415569330805,1744060570.3771403,2.121258497238159,0.0026744851096756634,1744060570.3771422,2.121258497238159,0.0,1744060570.3771443,2.121258497238159,56568542496.923805,1744060570.3771453,2.121258497238159,0.0,1744060570.3771467,2.121258497238159,-4.7278663929162514e-14,1744060570.3771477,2.121258497238159,-0.00266287681002288,1744060570.3771489,2.121258497238159,-3.834542606158778e-24,1744060570.37715,2.121258497238159,10,1744060570.377151,2.121258497238159,0.0,1744060570.377152,2.121258497238159,-22627416989.969524,1744060570.377153,2.121258497238159,0.0,1744060570.3771539,2.121258497238159,28284271247.461903
+1744060570.3973408,2.141296625137329,-0.02231415569330805,1744060570.3973424,2.141296625137329,0.0026744851096756634,1744060570.3973446,2.141296625137329,0.0,1744060570.3973465,2.141296625137329,56568542496.923805,1744060570.3973477,2.141296625137329,0.0,1744060570.3973489,2.141296625137329,-4.7278663929162514e-14,1744060570.3973498,2.141296625137329,-0.00266287681002288,1744060570.3973513,2.141296625137329,-3.834542606158778e-24,1744060570.3973522,2.141296625137329,10,1744060570.3973532,2.141296625137329,0.0,1744060570.3973541,2.141296625137329,-22627416989.969524,1744060570.3973553,2.141296625137329,0.0,1744060570.397356,2.141296625137329,28284271247.461903
+1744060570.4170206,2.1612629890441895,-0.02231415569330805,1744060570.4170227,2.1612629890441895,0.0026744851096756634,1744060570.417025,2.1612629890441895,0.0,1744060570.417027,2.1612629890441895,56568542496.923805,1744060570.4170282,2.1612629890441895,0.0,1744060570.4170294,2.1612629890441895,-4.7278663929162514e-14,1744060570.4170306,2.1612629890441895,-0.00266287681002288,1744060570.4170318,2.1612629890441895,-3.834542606158778e-24,1744060570.417033,2.1612629890441895,10,1744060570.417034,2.1612629890441895,0.0,1744060570.4170349,2.1612629890441895,-22627416989.969524,1744060570.4170358,2.1612629890441895,0.0,1744060570.4170368,2.1612629890441895,28284271247.461903
+1744060570.437116,2.181236743927002,-0.02231415569330805,1744060570.437118,2.181236743927002,0.0026744851096756634,1744060570.43712,2.181236743927002,0.0,1744060570.437122,2.181236743927002,56568542496.923805,1744060570.437123,2.181236743927002,0.0,1744060570.4371245,2.181236743927002,-4.7278663929162514e-14,1744060570.437126,2.181236743927002,-0.00266287681002288,1744060570.4371269,2.181236743927002,-3.834542606158778e-24,1744060570.4371285,2.181236743927002,10,1744060570.4371295,2.181236743927002,0.0,1744060570.4371302,2.181236743927002,-22627416989.969524,1744060570.4371314,2.181236743927002,0.0,1744060570.4371326,2.181236743927002,28284271247.461903
+1744060570.458182,2.2012691497802734,-0.02231415569330805,1744060570.4581845,2.2012691497802734,0.0026744851096756634,1744060570.4581864,2.2012691497802734,0.0,1744060570.4581885,2.2012691497802734,56568542496.923805,1744060570.4581895,2.2012691497802734,0.0,1744060570.458191,2.2012691497802734,-4.7278663929162514e-14,1744060570.458192,2.2012691497802734,-0.00266287681002288,1744060570.458193,2.2012691497802734,-3.834542606158778e-24,1744060570.4581945,2.2012691497802734,10,1744060570.4581954,2.2012691497802734,0.0,1744060570.4581962,2.2012691497802734,-22627416989.969524,1744060570.4581976,2.2012691497802734,0.0,1744060570.4581985,2.2012691497802734,28284271247.461903
+1744060570.4769306,2.2212326526641846,-0.02231415569330805,1744060570.4769335,2.2212326526641846,0.0026744851096756634,1744060570.476936,2.2212326526641846,0.0,1744060570.4769676,2.2212326526641846,56568542496.923805,1744060570.4769692,2.2212326526641846,0.0,1744060570.4769707,2.2212326526641846,-4.7278663929162514e-14,1744060570.476972,2.2212326526641846,-0.00266287681002288,1744060570.4769738,2.2212326526641846,-3.834542606158778e-24,1744060570.4769754,2.2212326526641846,10,1744060570.4769766,2.2212326526641846,0.0,1744060570.4769778,2.2212326526641846,-22627416989.969524,1744060570.4769793,2.2212326526641846,0.0,1744060570.4769807,2.2212326526641846,28284271247.461903
+1744060570.4970582,2.2412428855895996,-0.02231415569330805,1744060570.4970603,2.2412428855895996,0.0026744851096756634,1744060570.497063,2.2412428855895996,0.0,1744060570.4970646,2.2412428855895996,56568542496.923805,1744060570.497066,2.2412428855895996,0.0,1744060570.497067,2.2412428855895996,-4.7278663929162514e-14,1744060570.4970684,2.2412428855895996,-0.00266287681002288,1744060570.4970694,2.2412428855895996,-3.834542606158778e-24,1744060570.4970706,2.2412428855895996,10,1744060570.4970715,2.2412428855895996,0.0,1744060570.4970727,2.2412428855895996,-22627416989.969524,1744060570.4970737,2.2412428855895996,0.0,1744060570.4970746,2.2412428855895996,28284271247.461903
+1744060570.5171266,2.261232614517212,-0.02231415569330805,1744060570.5171287,2.261232614517212,0.0026744851096756634,1744060570.517131,2.261232614517212,0.0,1744060570.5171328,2.261232614517212,56568542496.923805,1744060570.5171337,2.261232614517212,0.0,1744060570.5171351,2.261232614517212,-4.7278663929162514e-14,1744060570.5171363,2.261232614517212,-0.00266287681002288,1744060570.5171373,2.261232614517212,-3.834542606158778e-24,1744060570.5171385,2.261232614517212,10,1744060570.5171394,2.261232614517212,0.0,1744060570.5171404,2.261232614517212,-22627416989.969524,1744060570.5171413,2.261232614517212,0.0,1744060570.5171423,2.261232614517212,28284271247.461903
+1744060570.537621,2.2812397480010986,-0.02231415569330805,1744060570.5376248,2.2812397480010986,0.0026744851096756634,1744060570.5376296,2.2812397480010986,0.0,1744060570.5376322,2.2812397480010986,56568542496.923805,1744060570.5376332,2.2812397480010986,0.0,1744060570.5376348,2.2812397480010986,-4.7278663929162514e-14,1744060570.5376363,2.2812397480010986,-0.00266287681002288,1744060570.5376377,2.2812397480010986,-3.834542606158778e-24,1744060570.537639,2.2812397480010986,10,1744060570.5376399,2.2812397480010986,0.0,1744060570.537641,2.2812397480010986,-22627416989.969524,1744060570.5376422,2.2812397480010986,0.0,1744060570.5376434,2.2812397480010986,28284271247.461903
+1744060570.5573246,2.301239252090454,-0.02231415569330805,1744060570.5573263,2.301239252090454,0.0026744851096756634,1744060570.5573287,2.301239252090454,0.0,1744060570.5573306,2.301239252090454,56568542496.923805,1744060570.5573318,2.301239252090454,0.0,1744060570.557333,2.301239252090454,-4.7278663929162514e-14,1744060570.5573342,2.301239252090454,-0.00266287681002288,1744060570.5573354,2.301239252090454,-3.834542606158778e-24,1744060570.5573366,2.301239252090454,10,1744060570.5573375,2.301239252090454,0.0,1744060570.5573387,2.301239252090454,-22627416989.969524,1744060570.5573394,2.301239252090454,0.0,1744060570.5573404,2.301239252090454,28284271247.461903
+1744060570.5770016,2.321228504180908,-0.02231415569330805,1744060570.5770035,2.321228504180908,0.0026744851096756634,1744060570.5770066,2.321228504180908,0.0,1744060570.5770092,2.321228504180908,56568542496.923805,1744060570.5770102,2.321228504180908,0.0,1744060570.5770113,2.321228504180908,-4.7278663929162514e-14,1744060570.577013,2.321228504180908,-0.00266287681002288,1744060570.5770144,2.321228504180908,-3.834542606158778e-24,1744060570.5770159,2.321228504180908,10,1744060570.5770168,2.321228504180908,0.0,1744060570.5770178,2.321228504180908,-22627416989.969524,1744060570.577019,2.321228504180908,0.0,1744060570.5770202,2.321228504180908,28284271247.461903
+1744060570.597207,2.3412423133850098,-0.02231415569330805,1744060570.5972087,2.3412423133850098,0.0026744851096756634,1744060570.5972111,2.3412423133850098,0.0,1744060570.5972135,2.3412423133850098,56568542496.923805,1744060570.5972147,2.3412423133850098,0.0,1744060570.5972164,2.3412423133850098,-4.7278663929162514e-14,1744060570.5972173,2.3412423133850098,-0.00266287681002288,1744060570.5972185,2.3412423133850098,-3.834542606158778e-24,1744060570.59722,2.3412423133850098,10,1744060570.597221,2.3412423133850098,0.0,1744060570.5972216,2.3412423133850098,-22627416989.969524,1744060570.5972226,2.3412423133850098,0.0,1744060570.5972238,2.3412423133850098,28284271247.461903
+1744060570.617122,2.361232042312622,-0.02231415569330805,1744060570.6171238,2.361232042312622,0.0026744851096756634,1744060570.6171262,2.361232042312622,0.0,1744060570.6171281,2.361232042312622,56568542496.923805,1744060570.6171293,2.361232042312622,0.0,1744060570.6171305,2.361232042312622,-4.7278663929162514e-14,1744060570.6171317,2.361232042312622,-0.00266287681002288,1744060570.617133,2.361232042312622,-3.834542606158778e-24,1744060570.6171339,2.361232042312622,10,1744060570.6171348,2.361232042312622,0.0,1744060570.6171358,2.361232042312622,-22627416989.969524,1744060570.6171367,2.361232042312622,0.0,1744060570.6171377,2.361232042312622,28284271247.461903
+1744060570.6371915,2.3812379837036133,-0.02231415569330805,1744060570.6371944,2.3812379837036133,0.0026744851096756634,1744060570.6371977,2.3812379837036133,0.0,1744060570.6372004,2.3812379837036133,56568542496.923805,1744060570.6372013,2.3812379837036133,0.0,1744060570.6372027,2.3812379837036133,-4.7278663929162514e-14,1744060570.6372037,2.3812379837036133,-0.00266287681002288,1744060570.637205,2.3812379837036133,-3.834542606158778e-24,1744060570.6372066,2.3812379837036133,10,1744060570.6372082,2.3812379837036133,0.0,1744060570.6372097,2.3812379837036133,-22627416989.969524,1744060570.6372116,2.3812379837036133,0.0,1744060570.6372135,2.3812379837036133,28284271247.461903
+1744060570.657641,2.401237964630127,-0.02231415569330805,1744060570.6576433,2.401237964630127,0.0026744851096756634,1744060570.6576464,2.401237964630127,0.0,1744060570.6576488,2.401237964630127,56568542496.923805,1744060570.65765,2.401237964630127,0.0,1744060570.6576514,2.401237964630127,-4.7278663929162514e-14,1744060570.657653,2.401237964630127,-0.00266287681002288,1744060570.657654,2.401237964630127,-3.834542606158778e-24,1744060570.6576552,2.401237964630127,10,1744060570.6576567,2.401237964630127,0.0,1744060570.6576576,2.401237964630127,-22627416989.969524,1744060570.6576586,2.401237964630127,0.0,1744060570.6576605,2.401237964630127,28284271247.461903
+1744060570.677039,2.4212427139282227,-0.02231415569330805,1744060570.6770406,2.4212427139282227,0.0026744851096756634,1744060570.6770432,2.4212427139282227,0.0,1744060570.6770456,2.4212427139282227,56568542496.923805,1744060570.6770463,2.4212427139282227,0.0,1744060570.6770475,2.4212427139282227,-4.7278663929162514e-14,1744060570.677049,2.4212427139282227,-0.00266287681002288,1744060570.6770499,2.4212427139282227,-3.834542606158778e-24,1744060570.677051,2.4212427139282227,10,1744060570.6770523,2.4212427139282227,0.0,1744060570.6770535,2.4212427139282227,-22627416989.969524,1744060570.6770546,2.4212427139282227,0.0,1744060570.6770566,2.4212427139282227,28284271247.461903
+1744060570.697267,2.441270351409912,-0.02231415569330805,1744060570.697269,2.441270351409912,0.0026744851096756634,1744060570.697271,2.441270351409912,0.0,1744060570.697273,2.441270351409912,56568542496.923805,1744060570.6972742,2.441270351409912,0.0,1744060570.6972754,2.441270351409912,-4.7278663929162514e-14,1744060570.6972764,2.441270351409912,-0.00266287681002288,1744060570.6972775,2.441270351409912,-3.834542606158778e-24,1744060570.6972787,2.441270351409912,10,1744060570.6972795,2.441270351409912,0.0,1744060570.6972804,2.441270351409912,-22627416989.969524,1744060570.6972816,2.441270351409912,0.0,1744060570.6972826,2.441270351409912,28284271247.461903
+1744060570.717412,2.461338520050049,-0.02231415569330805,1744060570.717414,2.461338520050049,0.0026744851096756634,1744060570.7174172,2.461338520050049,0.0,1744060570.7174196,2.461338520050049,56568542496.923805,1744060570.7174206,2.461338520050049,0.0,1744060570.7174218,2.461338520050049,-4.7278663929162514e-14,1744060570.717423,2.461338520050049,-0.00266287681002288,1744060570.7174242,2.461338520050049,-3.834542606158778e-24,1744060570.717425,2.461338520050049,10,1744060570.717426,2.461338520050049,0.0,1744060570.7174273,2.461338520050049,-22627416989.969524,1744060570.7174282,2.461338520050049,0.0,1744060570.717429,2.461338520050049,28284271247.461903
+1744060570.7369976,2.481273651123047,-0.02231415569330805,1744060570.7369998,2.481273651123047,0.0026744851096756634,1744060570.737002,2.481273651123047,0.0,1744060570.737005,2.481273651123047,56568542496.923805,1744060570.737007,2.481273651123047,0.0,1744060570.737009,2.481273651123047,-4.7278663929162514e-14,1744060570.737011,2.481273651123047,-0.00266287681002288,1744060570.7370124,2.481273651123047,-3.834542606158778e-24,1744060570.7370148,2.481273651123047,10,1744060570.7370167,2.481273651123047,0.0,1744060570.737018,2.481273651123047,-22627416989.969524,1744060570.73702,2.481273651123047,0.0,1744060570.7370217,2.481273651123047,28284271247.461903
+1744060570.7573738,2.5012803077697754,-0.022573782407336155,1744060570.7573752,2.5012803077697754,0.0022910956018205404,1744060570.7573779,2.5012803077697754,0.0,1744060570.7573798,2.5012803077697754,56568542496.923805,1744060570.757381,2.5012803077697754,0.0,1744060570.7573822,2.5012803077697754,-4.0501230908401356e-14,1744060570.7573833,2.5012803077697754,-0.002311176099265152,1744060570.7573845,2.5012803077697754,-3.3280935827038305e-24,1744060570.7573857,2.5012803077697754,10,1744060570.7573867,2.5012803077697754,0.0,1744060570.7573876,2.5012803077697754,-22627416989.969524,1744060570.7573886,2.5012803077697754,0.0,1744060570.7573895,2.5012803077697754,28284271247.461903
+1744060570.7770076,2.521228790283203,-0.022573782407336155,1744060570.7770097,2.521228790283203,0.0022910956018205404,1744060570.7770119,2.521228790283203,0.0,1744060570.7770143,2.521228790283203,56568542496.923805,1744060570.777015,2.521228790283203,0.0,1744060570.7770164,2.521228790283203,-4.0501230908401356e-14,1744060570.7770176,2.521228790283203,-0.002311176099265152,1744060570.7770185,2.521228790283203,-3.3280935827038305e-24,1744060570.77702,2.521228790283203,10,1744060570.7770207,2.521228790283203,0.0,1744060570.7770216,2.521228790283203,-22627416989.969524,1744060570.7770228,2.521228790283203,0.0,1744060570.777024,2.521228790283203,28284271247.461903
+1744060570.7969756,2.5412423610687256,-0.022573782407336155,1744060570.7969775,2.5412423610687256,0.0022910956018205404,1744060570.7969794,2.5412423610687256,0.0,1744060570.7969816,2.5412423610687256,56568542496.923805,1744060570.7969825,2.5412423610687256,0.0,1744060570.7969837,2.5412423610687256,-4.0501230908401356e-14,1744060570.796985,2.5412423610687256,-0.002311176099265152,1744060570.796986,2.5412423610687256,-3.3280935827038305e-24,1744060570.796987,2.5412423610687256,10,1744060570.7969882,2.5412423610687256,0.0,1744060570.796989,2.5412423610687256,-22627416989.969524,1744060570.79699,2.5412423610687256,0.0,1744060570.7969909,2.5412423610687256,28284271247.461903
+1744060570.8172948,2.561239242553711,-0.022573782407336155,1744060570.817297,2.561239242553711,0.0022910956018205404,1744060570.8172991,2.561239242553711,0.0,1744060570.8173013,2.561239242553711,56568542496.923805,1744060570.8173022,2.561239242553711,0.0,1744060570.8173037,2.561239242553711,-4.0501230908401356e-14,1744060570.8173048,2.561239242553711,-0.002311176099265152,1744060570.8173058,2.561239242553711,-3.3280935827038305e-24,1744060570.8173072,2.561239242553711,10,1744060570.817308,2.561239242553711,0.0,1744060570.817309,2.561239242553711,-22627416989.969524,1744060570.8173099,2.561239242553711,0.0,1744060570.817311,2.561239242553711,28284271247.461903
+1744060570.8369346,2.5812370777130127,-0.022573782407336155,1744060570.8369365,2.5812370777130127,0.0022910956018205404,1744060570.8369389,2.5812370777130127,0.0,1744060570.8369408,2.5812370777130127,56568542496.923805,1744060570.8369417,2.5812370777130127,0.0,1744060570.836943,2.5812370777130127,-4.0501230908401356e-14,1744060570.836944,2.5812370777130127,-0.002311176099265152,1744060570.836945,2.5812370777130127,-3.3280935827038305e-24,1744060570.8369467,2.5812370777130127,10,1744060570.8369477,2.5812370777130127,0.0,1744060570.8369484,2.5812370777130127,-22627416989.969524,1744060570.8369496,2.5812370777130127,0.0,1744060570.8369505,2.5812370777130127,28284271247.461903
+1744060570.8583705,2.601252555847168,-0.022573782407336155,1744060570.8583739,2.601252555847168,0.0022910956018205404,1744060570.8583763,2.601252555847168,0.0,1744060570.8583786,2.601252555847168,56568542496.923805,1744060570.85838,2.601252555847168,0.0,1744060570.858382,2.601252555847168,-4.0501230908401356e-14,1744060570.858384,2.601252555847168,-0.002311176099265152,1744060570.858385,2.601252555847168,-3.3280935827038305e-24,1744060570.8583863,2.601252555847168,10,1744060570.8583875,2.601252555847168,0.0,1744060570.8583887,2.601252555847168,-22627416989.969524,1744060570.85839,2.601252555847168,0.0,1744060570.858391,2.601252555847168,28284271247.461903
+1744060570.8781354,2.621626615524292,-0.022573782407336155,1744060570.87814,2.621626615524292,0.0022910956018205404,1744060570.8781476,2.621626615524292,0.0,1744060570.8781536,2.621626615524292,56568542496.923805,1744060570.878172,2.621626615524292,0.0,1744060570.8781755,2.621626615524292,-4.0501230908401356e-14,1744060570.878197,2.621626615524292,-0.002311176099265152,1744060570.8781998,2.621626615524292,-3.3280935827038305e-24,1744060570.878203,2.621626615524292,10,1744060570.8782065,2.621626615524292,0.0,1744060570.8782096,2.621626615524292,-22627416989.969524,1744060570.8782125,2.621626615524292,0.0,1744060570.8782148,2.621626615524292,28284271247.461903
+1744060570.8972359,2.6412642002105713,-0.022573782407336155,1744060570.8972383,2.6412642002105713,0.0022910956018205404,1744060570.8972404,2.6412642002105713,0.0,1744060570.8972425,2.6412642002105713,56568542496.923805,1744060570.8972437,2.6412642002105713,0.0,1744060570.897245,2.6412642002105713,-4.0501230908401356e-14,1744060570.897246,2.6412642002105713,-0.002311176099265152,1744060570.897247,2.6412642002105713,-3.3280935827038305e-24,1744060570.8972483,2.6412642002105713,10,1744060570.897249,2.6412642002105713,0.0,1744060570.89725,2.6412642002105713,-22627416989.969524,1744060570.8972511,2.6412642002105713,0.0,1744060570.8972518,2.6412642002105713,28284271247.461903
+1744060570.916894,2.6612300872802734,-0.022573782407336155,1744060570.9168956,2.6612300872802734,0.0022910956018205404,1744060570.916898,2.6612300872802734,0.0,1744060570.9169004,2.6612300872802734,56568542496.923805,1744060570.9169014,2.6612300872802734,0.0,1744060570.9169025,2.6612300872802734,-4.0501230908401356e-14,1744060570.9169037,2.6612300872802734,-0.002311176099265152,1744060570.9169047,2.6612300872802734,-3.3280935827038305e-24,1744060570.9169059,2.6612300872802734,10,1744060570.916907,2.6612300872802734,0.0,1744060570.916908,2.6612300872802734,-22627416989.969524,1744060570.916909,2.6612300872802734,0.0,1744060570.9169102,2.6612300872802734,28284271247.461903
+1744060570.936941,2.6812379360198975,-0.022573782407336155,1744060570.9369426,2.6812379360198975,0.0022910956018205404,1744060570.9369447,2.6812379360198975,0.0,1744060570.9369466,2.6812379360198975,56568542496.923805,1744060570.9369478,2.6812379360198975,0.0,1744060570.9369488,2.6812379360198975,-4.0501230908401356e-14,1744060570.93695,2.6812379360198975,-0.002311176099265152,1744060570.936951,2.6812379360198975,-3.3280935827038305e-24,1744060570.9369528,2.6812379360198975,10,1744060570.9369538,2.6812379360198975,0.0,1744060570.9369547,2.6812379360198975,-22627416989.969524,1744060570.9369557,2.6812379360198975,0.0,1744060570.9369566,2.6812379360198975,28284271247.461903
+1744060570.957478,2.7012739181518555,-0.022573782407336155,1744060570.95748,2.7012739181518555,0.0022910956018205404,1744060570.957482,2.7012739181518555,0.0,1744060570.9574842,2.7012739181518555,56568542496.923805,1744060570.9574852,2.7012739181518555,0.0,1744060570.9574866,2.7012739181518555,-4.0501230908401356e-14,1744060570.9575036,2.7012739181518555,-0.002311176099265152,1744060570.9575047,2.7012739181518555,-3.3280935827038305e-24,1744060570.957506,2.7012739181518555,10,1744060570.9575071,2.7012739181518555,0.0,1744060570.9575083,2.7012739181518555,-22627416989.969524,1744060570.9575093,2.7012739181518555,0.0,1744060570.9575105,2.7012739181518555,28284271247.461903
+1744060570.9770765,2.721266269683838,-0.022573782407336155,1744060570.9770782,2.721266269683838,0.0022910956018205404,1744060570.9770803,2.721266269683838,0.0,1744060570.9770823,2.721266269683838,56568542496.923805,1744060570.9770834,2.721266269683838,0.0,1744060570.9770846,2.721266269683838,-4.0501230908401356e-14,1744060570.9770856,2.721266269683838,-0.002311176099265152,1744060570.977087,2.721266269683838,-3.3280935827038305e-24,1744060570.977088,2.721266269683838,10,1744060570.977089,2.721266269683838,0.0,1744060570.9770901,2.721266269683838,-22627416989.969524,1744060570.977091,2.721266269683838,0.0,1744060570.9770923,2.721266269683838,28284271247.461903
+1744060570.9970303,2.741239070892334,-0.022573782407336155,1744060570.9970322,2.741239070892334,0.0022910956018205404,1744060570.9970343,2.741239070892334,0.0,1744060570.9970362,2.741239070892334,56568542496.923805,1744060570.9970374,2.741239070892334,0.0,1744060570.9970386,2.741239070892334,-4.0501230908401356e-14,1744060570.9970398,2.741239070892334,-0.002311176099265152,1744060570.997041,2.741239070892334,-3.3280935827038305e-24,1744060570.997042,2.741239070892334,10,1744060570.997043,2.741239070892334,0.0,1744060570.997044,2.741239070892334,-22627416989.969524,1744060570.9970448,2.741239070892334,0.0,1744060570.9970458,2.741239070892334,28284271247.461903
+1744060571.01688,2.761230230331421,-0.022573782407336155,1744060571.016882,2.761230230331421,0.0022910956018205404,1744060571.0168839,2.761230230331421,0.0,1744060571.016886,2.761230230331421,56568542496.923805,1744060571.016887,2.761230230331421,0.0,1744060571.0168884,2.761230230331421,-4.0501230908401356e-14,1744060571.0168896,2.761230230331421,-0.002311176099265152,1744060571.0168905,2.761230230331421,-3.3280935827038305e-24,1744060571.016892,2.761230230331421,10,1744060571.0168927,2.761230230331421,0.0,1744060571.0168936,2.761230230331421,-22627416989.969524,1744060571.0168948,2.761230230331421,0.0,1744060571.0168958,2.761230230331421,28284271247.461903
+1744060571.0380113,2.781296730041504,-0.022573782407336155,1744060571.0380135,2.781296730041504,0.0022910956018205404,1744060571.0380163,2.781296730041504,0.0,1744060571.0380185,2.781296730041504,56568542496.923805,1744060571.03802,2.781296730041504,0.0,1744060571.0380213,2.781296730041504,-4.0501230908401356e-14,1744060571.038023,2.781296730041504,-0.002311176099265152,1744060571.0380247,2.781296730041504,-3.3280935827038305e-24,1744060571.0380263,2.781296730041504,10,1744060571.0380278,2.781296730041504,0.0,1744060571.038029,2.781296730041504,-22627416989.969524,1744060571.0380306,2.781296730041504,0.0,1744060571.0380316,2.781296730041504,28284271247.461903
+1744060571.0573149,2.801274061203003,-0.022573782407336155,1744060571.0573165,2.801274061203003,0.0022910956018205404,1744060571.057319,2.801274061203003,0.0,1744060571.0573213,2.801274061203003,56568542496.923805,1744060571.0573223,2.801274061203003,0.0,1744060571.0573235,2.801274061203003,-4.0501230908401356e-14,1744060571.057325,2.801274061203003,-0.002311176099265152,1744060571.0573258,2.801274061203003,-3.3280935827038305e-24,1744060571.057327,2.801274061203003,10,1744060571.0573282,2.801274061203003,0.0,1744060571.0573292,2.801274061203003,-22627416989.969524,1744060571.0573301,2.801274061203003,0.0,1744060571.057331,2.801274061203003,28284271247.461903
+1744060571.07693,2.821232557296753,-0.022573782407336155,1744060571.076932,2.821232557296753,0.0022910956018205404,1744060571.0769343,2.821232557296753,0.0,1744060571.0769365,2.821232557296753,56568542496.923805,1744060571.0769372,2.821232557296753,0.0,1744060571.0769384,2.821232557296753,-4.0501230908401356e-14,1744060571.0769398,2.821232557296753,-0.002311176099265152,1744060571.076941,2.821232557296753,-3.3280935827038305e-24,1744060571.076942,2.821232557296753,10,1744060571.0769432,2.821232557296753,0.0,1744060571.0769439,2.821232557296753,-22627416989.969524,1744060571.0769448,2.821232557296753,0.0,1744060571.076946,2.821232557296753,28284271247.461903
+1744060571.0971334,2.8412630558013916,-0.022573782407336155,1744060571.0971353,2.8412630558013916,0.0022910956018205404,1744060571.0971375,2.8412630558013916,0.0,1744060571.0971394,2.8412630558013916,56568542496.923805,1744060571.0971406,2.8412630558013916,0.0,1744060571.0971417,2.8412630558013916,-4.0501230908401356e-14,1744060571.0971427,2.8412630558013916,-0.002311176099265152,1744060571.097144,2.8412630558013916,-3.3280935827038305e-24,1744060571.097145,2.8412630558013916,10,1744060571.097146,2.8412630558013916,0.0,1744060571.097147,2.8412630558013916,-22627416989.969524,1744060571.097148,2.8412630558013916,0.0,1744060571.097149,2.8412630558013916,28284271247.461903
+1744060571.1170866,2.8612446784973145,-0.022573782407336155,1744060571.1170893,2.8612446784973145,0.0022910956018205404,1744060571.1170926,2.8612446784973145,0.0,1744060571.1170952,2.8612446784973145,56568542496.923805,1744060571.117114,2.8612446784973145,0.0,1744060571.1171155,2.8612446784973145,-4.0501230908401356e-14,1744060571.117117,2.8612446784973145,-0.002311176099265152,1744060571.1171184,2.8612446784973145,-3.3280935827038305e-24,1744060571.11712,2.8612446784973145,10,1744060571.117121,2.8612446784973145,0.0,1744060571.1171217,2.8612446784973145,-22627416989.969524,1744060571.1171231,2.8612446784973145,0.0,1744060571.117124,2.8612446784973145,28284271247.461903
+1744060571.1370618,2.881239891052246,-0.022573782407336155,1744060571.1370637,2.881239891052246,0.0022910956018205404,1744060571.1370656,2.881239891052246,0.0,1744060571.137068,2.881239891052246,56568542496.923805,1744060571.137069,2.881239891052246,0.0,1744060571.1370702,2.881239891052246,-4.0501230908401356e-14,1744060571.1370714,2.881239891052246,-0.002311176099265152,1744060571.1370723,2.881239891052246,-3.3280935827038305e-24,1744060571.1370735,2.881239891052246,10,1744060571.1370745,2.881239891052246,0.0,1744060571.1370754,2.881239891052246,-22627416989.969524,1744060571.1370764,2.881239891052246,0.0,1744060571.1370776,2.881239891052246,28284271247.461903
+1744060571.1572871,2.9012398719787598,-0.022573782407336155,1744060571.15729,2.9012398719787598,0.0022910956018205404,1744060571.1572921,2.9012398719787598,0.0,1744060571.1572943,2.9012398719787598,56568542496.923805,1744060571.1572955,2.9012398719787598,0.0,1744060571.1572967,2.9012398719787598,-4.0501230908401356e-14,1744060571.1572978,2.9012398719787598,-0.002311176099265152,1744060571.157299,2.9012398719787598,-3.3280935827038305e-24,1744060571.1573005,2.9012398719787598,10,1744060571.1573014,2.9012398719787598,0.0,1744060571.1573026,2.9012398719787598,-22627416989.969524,1744060571.1573036,2.9012398719787598,0.0,1744060571.1573043,2.9012398719787598,28284271247.461903
+1744060571.1771092,2.921267509460449,-0.022573782407336155,1744060571.1771114,2.921267509460449,0.0022910956018205404,1744060571.1771135,2.921267509460449,0.0,1744060571.1771157,2.921267509460449,56568542496.923805,1744060571.1771166,2.921267509460449,0.0,1744060571.177118,2.921267509460449,-4.0501230908401356e-14,1744060571.1771193,2.921267509460449,-0.002311176099265152,1744060571.1771202,2.921267509460449,-3.3280935827038305e-24,1744060571.1771212,2.921267509460449,10,1744060571.1771224,2.921267509460449,0.0,1744060571.1771233,2.921267509460449,-22627416989.969524,1744060571.1771243,2.921267509460449,0.0,1744060571.1771255,2.921267509460449,28284271247.461903
+1744060571.1972415,2.9412877559661865,-0.022573782407336155,1744060571.1972437,2.9412877559661865,0.0022910956018205404,1744060571.1972468,2.9412877559661865,0.0,1744060571.1972501,2.9412877559661865,56568542496.923805,1744060571.1972523,2.9412877559661865,0.0,1744060571.1972547,2.9412877559661865,-4.0501230908401356e-14,1744060571.1972566,2.9412877559661865,-0.002311176099265152,1744060571.197259,2.9412877559661865,-3.3280935827038305e-24,1744060571.1972613,2.9412877559661865,10,1744060571.1972632,2.9412877559661865,0.0,1744060571.1972647,2.9412877559661865,-22627416989.969524,1744060571.197266,2.9412877559661865,0.0,1744060571.1972675,2.9412877559661865,28284271247.461903
+1744060571.2170036,2.9612624645233154,-0.022573782407336155,1744060571.2170055,2.9612624645233154,0.0022910956018205404,1744060571.2170076,2.9612624645233154,0.0,1744060571.21701,2.9612624645233154,56568542496.923805,1744060571.2170107,2.9612624645233154,0.0,1744060571.217012,2.9612624645233154,-4.0501230908401356e-14,1744060571.2170312,2.9612624645233154,-0.002311176099265152,1744060571.2170324,2.9612624645233154,-3.3280935827038305e-24,1744060571.217034,2.9612624645233154,10,1744060571.217035,2.9612624645233154,0.0,1744060571.217036,2.9612624645233154,-22627416989.969524,1744060571.217037,2.9612624645233154,0.0,1744060571.2170382,2.9612624645233154,28284271247.461903
+1744060571.236952,2.9812381267547607,-0.022573782407336155,1744060571.236954,2.9812381267547607,0.0022910956018205404,1744060571.2369564,2.9812381267547607,0.0,1744060571.2369585,2.9812381267547607,56568542496.923805,1744060571.23696,2.9812381267547607,0.0,1744060571.236962,2.9812381267547607,-4.0501230908401356e-14,1744060571.2369637,2.9812381267547607,-0.002311176099265152,1744060571.2369657,2.9812381267547607,-3.3280935827038305e-24,1744060571.2369676,2.9812381267547607,10,1744060571.2369695,2.9812381267547607,0.0,1744060571.236971,2.9812381267547607,-22627416989.969524,1744060571.2369726,2.9812381267547607,0.0,1744060571.2369742,2.9812381267547607,28284271247.461903
+1744060571.2572432,3.0012378692626953,-0.025996626646578067,1744060571.2572448,3.0012378692626953,0.0060652351098486185,1744060571.2572467,3.0012378692626953,0.0,1744060571.2572489,3.0012378692626953,56568542496.923805,1744060571.2572498,3.0012378692626953,0.0,1744060571.2572508,3.0012378692626953,-1.0721922188777726e-13,1744060571.257252,3.0012378692626953,-0.00607939800024131,1744060571.2572532,3.0012378692626953,-8.754333119720415e-24,1744060571.2572541,3.0012378692626953,10,1744060571.257255,3.0012378692626953,0.0,1744060571.257256,3.0012378692626953,-22627416989.969524,1744060571.257257,3.0012378692626953,0.0,1744060571.257258,3.0012378692626953,28284271247.461903
+1744060571.2770128,3.021254301071167,-0.025996626646578067,1744060571.2770145,3.021254301071167,0.0060652351098486185,1744060571.2770169,3.021254301071167,0.0,1744060571.2770188,3.021254301071167,56568542496.923805,1744060571.27702,3.021254301071167,0.0,1744060571.277021,3.021254301071167,-1.0721922188777726e-13,1744060571.2770221,3.021254301071167,-0.00607939800024131,1744060571.2770236,3.021254301071167,-8.754333119720415e-24,1744060571.2770245,3.021254301071167,10,1744060571.2770255,3.021254301071167,0.0,1744060571.2770267,3.021254301071167,-22627416989.969524,1744060571.2770276,3.021254301071167,0.0,1744060571.2770283,3.021254301071167,28284271247.461903
+1744060571.2976055,3.0412797927856445,-0.025996626646578067,1744060571.2976077,3.0412797927856445,0.0060652351098486185,1744060571.29761,3.0412797927856445,0.0,1744060571.297612,3.0412797927856445,56568542496.923805,1744060571.2976131,3.0412797927856445,0.0,1744060571.2976143,3.0412797927856445,-1.0721922188777726e-13,1744060571.2976155,3.0412797927856445,-0.00607939800024131,1744060571.2976167,3.0412797927856445,-8.754333119720415e-24,1744060571.2976182,3.0412797927856445,10,1744060571.297619,3.0412797927856445,0.0,1744060571.2976203,3.0412797927856445,-22627416989.969524,1744060571.297621,3.0412797927856445,0.0,1744060571.297622,3.0412797927856445,28284271247.461903
+1744060571.3169925,3.0612306594848633,-0.025996626646578067,1744060571.3169959,3.0612306594848633,0.0060652351098486185,1744060571.316999,3.0612306594848633,0.0,1744060571.3170018,3.0612306594848633,56568542496.923805,1744060571.3170035,3.0612306594848633,0.0,1744060571.3170054,3.0612306594848633,-1.0721922188777726e-13,1744060571.3170068,3.0612306594848633,-0.00607939800024131,1744060571.3170085,3.0612306594848633,-8.754333119720415e-24,1744060571.31701,3.0612306594848633,10,1744060571.3170114,3.0612306594848633,0.0,1744060571.3170276,3.0612306594848633,-22627416989.969524,1744060571.3170288,3.0612306594848633,0.0,1744060571.3170307,3.0612306594848633,28284271247.461903
+1744060571.3371377,3.0812747478485107,-0.025996626646578067,1744060571.3371406,3.0812747478485107,0.0060652351098486185,1744060571.337143,3.0812747478485107,0.0,1744060571.337146,3.0812747478485107,56568542496.923805,1744060571.3371472,3.0812747478485107,0.0,1744060571.3371484,3.0812747478485107,-1.0721922188777726e-13,1744060571.3371499,3.0812747478485107,-0.00607939800024131,1744060571.3371515,3.0812747478485107,-8.754333119720415e-24,1744060571.3371532,3.0812747478485107,10,1744060571.3371544,3.0812747478485107,0.0,1744060571.3371556,3.0812747478485107,-22627416989.969524,1744060571.3371568,3.0812747478485107,0.0,1744060571.337158,3.0812747478485107,28284271247.461903
+1744060571.3574007,3.101271152496338,-0.025996626646578067,1744060571.3574023,3.101271152496338,0.0060652351098486185,1744060571.3574045,3.101271152496338,0.0,1744060571.3574064,3.101271152496338,56568542496.923805,1744060571.3574076,3.101271152496338,0.0,1744060571.3574088,3.101271152496338,-1.0721922188777726e-13,1744060571.3574097,3.101271152496338,-0.00607939800024131,1744060571.3574111,3.101271152496338,-8.754333119720415e-24,1744060571.357412,3.101271152496338,10,1744060571.357413,3.101271152496338,0.0,1744060571.3574145,3.101271152496338,-22627416989.969524,1744060571.3574152,3.101271152496338,0.0,1744060571.3574162,3.101271152496338,28284271247.461903
+1744060571.3769994,3.1212832927703857,-0.025996626646578067,1744060571.3770013,3.1212832927703857,0.0060652351098486185,1744060571.3770034,3.1212832927703857,0.0,1744060571.3770058,3.1212832927703857,56568542496.923805,1744060571.377007,3.1212832927703857,0.0,1744060571.3770084,3.1212832927703857,-1.0721922188777726e-13,1744060571.3770094,3.1212832927703857,-0.00607939800024131,1744060571.3770106,3.1212832927703857,-8.754333119720415e-24,1744060571.377012,3.1212832927703857,10,1744060571.377013,3.1212832927703857,0.0,1744060571.3770137,3.1212832927703857,-22627416989.969524,1744060571.3770149,3.1212832927703857,0.0,1744060571.3770409,3.1212832927703857,28284271247.461903
+1744060571.3970177,3.1412694454193115,-0.025996626646578067,1744060571.3970194,3.1412694454193115,0.0060652351098486185,1744060571.3970215,3.1412694454193115,0.0,1744060571.3970237,3.1412694454193115,56568542496.923805,1744060571.3970249,3.1412694454193115,0.0,1744060571.3970258,3.1412694454193115,-1.0721922188777726e-13,1744060571.397027,3.1412694454193115,-0.00607939800024131,1744060571.3970282,3.1412694454193115,-8.754333119720415e-24,1744060571.3970292,3.1412694454193115,10,1744060571.39703,3.1412694454193115,0.0,1744060571.397031,3.1412694454193115,-22627416989.969524,1744060571.3970323,3.1412694454193115,0.0,1744060571.3970332,3.1412694454193115,28284271247.461903
+1744060571.4170933,3.161257743835449,-0.025996626646578067,1744060571.4170954,3.161257743835449,0.0060652351098486185,1744060571.4170976,3.161257743835449,0.0,1744060571.4170995,3.161257743835449,56568542496.923805,1744060571.4171004,3.161257743835449,0.0,1744060571.4171016,3.161257743835449,-1.0721922188777726e-13,1744060571.4171028,3.161257743835449,-0.00607939800024131,1744060571.4171038,3.161257743835449,-8.754333119720415e-24,1744060571.4171052,3.161257743835449,10,1744060571.4171062,3.161257743835449,0.0,1744060571.4171069,3.161257743835449,-22627416989.969524,1744060571.417108,3.161257743835449,0.0,1744060571.417109,3.161257743835449,28284271247.461903
+1744060571.437026,3.1812665462493896,-0.025996626646578067,1744060571.437028,3.1812665462493896,0.0060652351098486185,1744060571.4370298,3.1812665462493896,0.0,1744060571.437032,3.1812665462493896,56568542496.923805,1744060571.4370327,3.1812665462493896,0.0,1744060571.437034,3.1812665462493896,-1.0721922188777726e-13,1744060571.4370353,3.1812665462493896,-0.00607939800024131,1744060571.4370363,3.1812665462493896,-8.754333119720415e-24,1744060571.4370375,3.1812665462493896,10,1744060571.4370387,3.1812665462493896,0.0,1744060571.4370396,3.1812665462493896,-22627416989.969524,1744060571.4370406,3.1812665462493896,0.0,1744060571.4370418,3.1812665462493896,28284271247.461903
+1744060571.4572306,3.2012760639190674,-0.025996626646578067,1744060571.4572325,3.2012760639190674,0.0060652351098486185,1744060571.4572344,3.2012760639190674,0.0,1744060571.4572365,3.2012760639190674,56568542496.923805,1744060571.4572375,3.2012760639190674,0.0,1744060571.4572387,3.2012760639190674,-1.0721922188777726e-13,1744060571.45724,3.2012760639190674,-0.00607939800024131,1744060571.457241,3.2012760639190674,-8.754333119720415e-24,1744060571.4572423,3.2012760639190674,10,1744060571.4572432,3.2012760639190674,0.0,1744060571.4572442,3.2012760639190674,-22627416989.969524,1744060571.457245,3.2012760639190674,0.0,1744060571.4572463,3.2012760639190674,28284271247.461903
+1744060571.4769735,3.2212696075439453,-0.025996626646578067,1744060571.4769754,3.2212696075439453,0.0060652351098486185,1744060571.4769773,3.2212696075439453,0.0,1744060571.4769797,3.2212696075439453,56568542496.923805,1744060571.4769807,3.2212696075439453,0.0,1744060571.476982,3.2212696075439453,-1.0721922188777726e-13,1744060571.4769833,3.2212696075439453,-0.00607939800024131,1744060571.4769843,3.2212696075439453,-8.754333119720415e-24,1744060571.4769857,3.2212696075439453,10,1744060571.4769866,3.2212696075439453,0.0,1744060571.4769876,3.2212696075439453,-22627416989.969524,1744060571.4769886,3.2212696075439453,0.0,1744060571.4769897,3.2212696075439453,28284271247.461903
+1744060571.4969962,3.2412402629852295,-0.025996626646578067,1744060571.496998,3.2412402629852295,0.0060652351098486185,1744060571.4970005,3.2412402629852295,0.0,1744060571.4970028,3.2412402629852295,56568542496.923805,1744060571.4970038,3.2412402629852295,0.0,1744060571.4970243,3.2412402629852295,-1.0721922188777726e-13,1744060571.4970255,3.2412402629852295,-0.00607939800024131,1744060571.4970264,3.2412402629852295,-8.754333119720415e-24,1744060571.4970276,3.2412402629852295,10,1744060571.4970286,3.2412402629852295,0.0,1744060571.4970295,3.2412402629852295,-22627416989.969524,1744060571.4970307,3.2412402629852295,0.0,1744060571.4970317,3.2412402629852295,28284271247.461903
+1744060571.5175004,3.2612521648406982,-0.025996626646578067,1744060571.5175033,3.2612521648406982,0.0060652351098486185,1744060571.5175064,3.2612521648406982,0.0,1744060571.51751,3.2612521648406982,56568542496.923805,1744060571.5175116,3.2612521648406982,0.0,1744060571.517514,3.2612521648406982,-1.0721922188777726e-13,1744060571.5175157,3.2612521648406982,-0.00607939800024131,1744060571.5175178,3.2612521648406982,-8.754333119720415e-24,1744060571.5175197,3.2612521648406982,10,1744060571.5175214,3.2612521648406982,0.0,1744060571.5175226,3.2612521648406982,-22627416989.969524,1744060571.5175238,3.2612521648406982,0.0,1744060571.5175247,3.2612521648406982,28284271247.461903
+1744060571.5369737,3.2812368869781494,-0.025996626646578067,1744060571.5369756,3.2812368869781494,0.0060652351098486185,1744060571.5369778,3.2812368869781494,0.0,1744060571.5369797,3.2812368869781494,56568542496.923805,1744060571.5369806,3.2812368869781494,0.0,1744060571.5369818,3.2812368869781494,-1.0721922188777726e-13,1744060571.536983,3.2812368869781494,-0.00607939800024131,1744060571.536984,3.2812368869781494,-8.754333119720415e-24,1744060571.5369854,3.2812368869781494,10,1744060571.536986,3.2812368869781494,0.0,1744060571.536987,3.2812368869781494,-22627416989.969524,1744060571.5369885,3.2812368869781494,0.0,1744060571.5369895,3.2812368869781494,28284271247.461903
+1744060571.5572345,3.3012781143188477,-0.025996626646578067,1744060571.5572362,3.3012781143188477,0.0060652351098486185,1744060571.5572383,3.3012781143188477,0.0,1744060571.5572402,3.3012781143188477,56568542496.923805,1744060571.5572414,3.3012781143188477,0.0,1744060571.5572426,3.3012781143188477,-1.0721922188777726e-13,1744060571.5572438,3.3012781143188477,-0.00607939800024131,1744060571.557245,3.3012781143188477,-8.754333119720415e-24,1744060571.557246,3.3012781143188477,10,1744060571.557247,3.3012781143188477,0.0,1744060571.557248,3.3012781143188477,-22627416989.969524,1744060571.557249,3.3012781143188477,0.0,1744060571.55725,3.3012781143188477,28284271247.461903
+1744060571.5770025,3.3212661743164062,-0.025996626646578067,1744060571.5770044,3.3212661743164062,0.0060652351098486185,1744060571.5770068,3.3212661743164062,0.0,1744060571.5770094,3.3212661743164062,56568542496.923805,1744060571.5770104,3.3212661743164062,0.0,1744060571.5770118,3.3212661743164062,-1.0721922188777726e-13,1744060571.5770135,3.3212661743164062,-0.00607939800024131,1744060571.5770144,3.3212661743164062,-8.754333119720415e-24,1744060571.5770164,3.3212661743164062,10,1744060571.5770173,3.3212661743164062,0.0,1744060571.5770183,3.3212661743164062,-22627416989.969524,1744060571.5770195,3.3212661743164062,0.0,1744060571.5770206,3.3212661743164062,28284271247.461903
+1744060571.597079,3.341244697570801,-0.025996626646578067,1744060571.5970812,3.341244697570801,0.0060652351098486185,1744060571.597083,3.341244697570801,0.0,1744060571.5970852,3.341244697570801,56568542496.923805,1744060571.5970862,3.341244697570801,0.0,1744060571.5970874,3.341244697570801,-1.0721922188777726e-13,1744060571.5970888,3.341244697570801,-0.00607939800024131,1744060571.59709,3.341244697570801,-8.754333119720415e-24,1744060571.597091,3.341244697570801,10,1744060571.5970922,3.341244697570801,0.0,1744060571.5970929,3.341244697570801,-22627416989.969524,1744060571.5970938,3.341244697570801,0.0,1744060571.597095,3.341244697570801,28284271247.461903
+1744060571.617231,3.361311912536621,-0.025996626646578067,1744060571.6172328,3.361311912536621,0.0060652351098486185,1744060571.617235,3.361311912536621,0.0,1744060571.617237,3.361311912536621,56568542496.923805,1744060571.617238,3.361311912536621,0.0,1744060571.6172392,3.361311912536621,-1.0721922188777726e-13,1744060571.6172404,3.361311912536621,-0.00607939800024131,1744060571.6172414,3.361311912536621,-8.754333119720415e-24,1744060571.6172426,3.361311912536621,10,1744060571.6172438,3.361311912536621,0.0,1744060571.6172447,3.361311912536621,-22627416989.969524,1744060571.6172457,3.361311912536621,0.0,1744060571.6172466,3.361311912536621,28284271247.461903
+1744060571.6370234,3.381265163421631,-0.025996626646578067,1744060571.6370254,3.381265163421631,0.0060652351098486185,1744060571.6370275,3.381265163421631,0.0,1744060571.6370296,3.381265163421631,56568542496.923805,1744060571.6370306,3.381265163421631,0.0,1744060571.637032,3.381265163421631,-1.0721922188777726e-13,1744060571.6370332,3.381265163421631,-0.00607939800024131,1744060571.6370344,3.381265163421631,-8.754333119720415e-24,1744060571.6370358,3.381265163421631,10,1744060571.6370368,3.381265163421631,0.0,1744060571.6370375,3.381265163421631,-22627416989.969524,1744060571.6370387,3.381265163421631,0.0,1744060571.6370397,3.381265163421631,28284271247.461903
+1744060571.6580367,3.4013302326202393,-0.025996626646578067,1744060571.6580389,3.4013302326202393,0.0060652351098486185,1744060571.658041,3.4013302326202393,0.0,1744060571.6580434,3.4013302326202393,56568542496.923805,1744060571.6580443,3.4013302326202393,0.0,1744060571.658046,3.4013302326202393,-1.0721922188777726e-13,1744060571.6580472,3.4013302326202393,-0.00607939800024131,1744060571.6580489,3.4013302326202393,-8.754333119720415e-24,1744060571.65805,3.4013302326202393,10,1744060571.6580513,3.4013302326202393,0.0,1744060571.6580524,3.4013302326202393,-22627416989.969524,1744060571.6580536,3.4013302326202393,0.0,1744060571.6580546,3.4013302326202393,28284271247.461903
+1744060571.677136,3.4212775230407715,-0.025996626646578067,1744060571.6771533,3.4212775230407715,0.0060652351098486185,1744060571.6771553,3.4212775230407715,0.0,1744060571.6771576,3.4212775230407715,56568542496.923805,1744060571.6771586,3.4212775230407715,0.0,1744060571.6771598,3.4212775230407715,-1.0721922188777726e-13,1744060571.677161,3.4212775230407715,-0.00607939800024131,1744060571.6771622,3.4212775230407715,-8.754333119720415e-24,1744060571.6771636,3.4212775230407715,10,1744060571.6771646,3.4212775230407715,0.0,1744060571.6771653,3.4212775230407715,-22627416989.969524,1744060571.6771662,3.4212775230407715,0.0,1744060571.6771674,3.4212775230407715,28284271247.461903
+1744060571.697023,3.4412412643432617,-0.025996626646578067,1744060571.6970248,3.4412412643432617,0.0060652351098486185,1744060571.697027,3.4412412643432617,0.0,1744060571.697029,3.4412412643432617,56568542496.923805,1744060571.6970303,3.4412412643432617,0.0,1744060571.6970317,3.4412412643432617,-1.0721922188777726e-13,1744060571.697033,3.4412412643432617,-0.00607939800024131,1744060571.697034,3.4412412643432617,-8.754333119720415e-24,1744060571.6970353,3.4412412643432617,10,1744060571.697036,3.4412412643432617,0.0,1744060571.697037,3.4412412643432617,-22627416989.969524,1744060571.6970382,3.4412412643432617,0.0,1744060571.6970391,3.4412412643432617,28284271247.461903
+1744060571.7170458,3.4612324237823486,-0.025996626646578067,1744060571.7170475,3.4612324237823486,0.0060652351098486185,1744060571.7170498,3.4612324237823486,0.0,1744060571.7170522,3.4612324237823486,56568542496.923805,1744060571.7170534,3.4612324237823486,0.0,1744060571.7170546,3.4612324237823486,-1.0721922188777726e-13,1744060571.717074,3.4612324237823486,-0.00607939800024131,1744060571.7170749,3.4612324237823486,-8.754333119720415e-24,1744060571.7170763,3.4612324237823486,10,1744060571.7170773,3.4612324237823486,0.0,1744060571.717078,3.4612324237823486,-22627416989.969524,1744060571.7170794,3.4612324237823486,0.0,1744060571.71708,3.4612324237823486,28284271247.461903
+1744060571.7368984,3.4812300205230713,-0.025996626646578067,1744060571.7369,3.4812300205230713,0.0060652351098486185,1744060571.7369025,3.4812300205230713,0.0,1744060571.7369046,3.4812300205230713,56568542496.923805,1744060571.7369058,3.4812300205230713,0.0,1744060571.736907,3.4812300205230713,-1.0721922188777726e-13,1744060571.736908,3.4812300205230713,-0.00607939800024131,1744060571.7369094,3.4812300205230713,-8.754333119720415e-24,1744060571.7369103,3.4812300205230713,10,1744060571.7369113,3.4812300205230713,0.0,1744060571.7369125,3.4812300205230713,-22627416989.969524,1744060571.7369134,3.4812300205230713,0.0,1744060571.7369142,3.4812300205230713,28284271247.461903
+1744060571.7575521,3.5012617111206055,-0.03947534816394446,1744060571.7575538,3.5012617111206055,0.004691898128173789,1744060571.757556,3.5012617111206055,0.0,1744060571.757558,3.5012617111206055,56568542496.923805,1744060571.757559,3.5012617111206055,0.0,1744060571.7575603,3.5012617111206055,-8.294182457371357e-14,1744060571.7575617,3.5012617111206055,-0.004672595157211377,1744060571.7575626,3.5012617111206055,-6.728537025899213e-24,1744060571.7575638,3.5012617111206055,10,1744060571.757565,3.5012617111206055,0.0,1744060571.757566,3.5012617111206055,-22627416989.969524,1744060571.7575667,3.5012617111206055,0.0,1744060571.7575676,3.5012617111206055,28284271247.461903
+1744060571.7770398,3.5212676525115967,-0.03947534816394446,1744060571.7770422,3.5212676525115967,0.004691898128173789,1744060571.7770443,3.5212676525115967,0.0,1744060571.7770464,3.5212676525115967,56568542496.923805,1744060571.7770476,3.5212676525115967,0.0,1744060571.7770488,3.5212676525115967,-8.294182457371357e-14,1744060571.7770498,3.5212676525115967,-0.004672595157211377,1744060571.7770512,3.5212676525115967,-6.728537025899213e-24,1744060571.7770522,3.5212676525115967,10,1744060571.7770534,3.5212676525115967,0.0,1744060571.7770543,3.5212676525115967,-22627416989.969524,1744060571.7770555,3.5212676525115967,0.0,1744060571.7770565,3.5212676525115967,28284271247.461903
+1744060571.797016,3.541238784790039,-0.03947534816394446,1744060571.7970178,3.541238784790039,0.004691898128173789,1744060571.79702,3.541238784790039,0.0,1744060571.7970219,3.541238784790039,56568542496.923805,1744060571.797023,3.541238784790039,0.0,1744060571.7970243,3.541238784790039,-8.294182457371357e-14,1744060571.7970254,3.541238784790039,-0.004672595157211377,1744060571.7970266,3.541238784790039,-6.728537025899213e-24,1744060571.7970278,3.541238784790039,10,1744060571.7970288,3.541238784790039,0.0,1744060571.7970297,3.541238784790039,-22627416989.969524,1744060571.7970307,3.541238784790039,0.0,1744060571.7970316,3.541238784790039,28284271247.461903
+1744060571.8173077,3.561258554458618,-0.03947534816394446,1744060571.8173118,3.561258554458618,0.004691898128173789,1744060571.817315,3.561258554458618,0.0,1744060571.8173175,3.561258554458618,56568542496.923805,1744060571.8173192,3.561258554458618,0.0,1744060571.8173206,3.561258554458618,-8.294182457371357e-14,1744060571.8173223,3.561258554458618,-0.004672595157211377,1744060571.817324,3.561258554458618,-6.728537025899213e-24,1744060571.8173256,3.561258554458618,10,1744060571.817327,3.561258554458618,0.0,1744060571.8173285,3.561258554458618,-22627416989.969524,1744060571.8173301,3.561258554458618,0.0,1744060571.8173316,3.561258554458618,28284271247.461903
+1744060571.836959,3.5812625885009766,-0.03947534816394446,1744060571.8369613,3.5812625885009766,0.004691898128173789,1744060571.8369637,3.5812625885009766,0.0,1744060571.8369656,3.5812625885009766,56568542496.923805,1744060571.8369668,3.5812625885009766,0.0,1744060571.836968,3.5812625885009766,-8.294182457371357e-14,1744060571.836969,3.5812625885009766,-0.004672595157211377,1744060571.83697,3.5812625885009766,-6.728537025899213e-24,1744060571.836971,3.5812625885009766,10,1744060571.836972,3.5812625885009766,0.0,1744060571.836973,3.5812625885009766,-22627416989.969524,1744060571.8369741,3.5812625885009766,0.0,1744060571.836975,3.5812625885009766,28284271247.461903
+1744060571.8575835,3.6012766361236572,-0.03947534816394446,1744060571.8575857,3.6012766361236572,0.004691898128173789,1744060571.8575873,3.6012766361236572,0.0,1744060571.8575897,3.6012766361236572,56568542496.923805,1744060571.8575907,3.6012766361236572,0.0,1744060571.8575923,3.6012766361236572,-8.294182457371357e-14,1744060571.8575933,3.6012766361236572,-0.004672595157211377,1744060571.8575947,3.6012766361236572,-6.728537025899213e-24,1744060571.8575957,3.6012766361236572,10,1744060571.8575966,3.6012766361236572,0.0,1744060571.8575976,3.6012766361236572,-22627416989.969524,1744060571.8575988,3.6012766361236572,0.0,1744060571.8575997,3.6012766361236572,28284271247.461903
+1744060571.8774748,3.6212754249572754,-0.03947534816394446,1744060571.877477,3.6212754249572754,0.004691898128173789,1744060571.877479,3.6212754249572754,0.0,1744060571.8774815,3.6212754249572754,56568542496.923805,1744060571.8774824,3.6212754249572754,0.0,1744060571.8774838,3.6212754249572754,-8.294182457371357e-14,1744060571.877485,3.6212754249572754,-0.004672595157211377,1744060571.8774862,3.6212754249572754,-6.728537025899213e-24,1744060571.8774874,3.6212754249572754,10,1744060571.8774886,3.6212754249572754,0.0,1744060571.8774893,3.6212754249572754,-22627416989.969524,1744060571.8775082,3.6212754249572754,0.0,1744060571.877509,3.6212754249572754,28284271247.461903
+1744060571.897049,3.641268730163574,-0.03947534816394446,1744060571.8970509,3.641268730163574,0.004691898128173789,1744060571.8970535,3.641268730163574,0.0,1744060571.8970556,3.641268730163574,56568542496.923805,1744060571.8970568,3.641268730163574,0.0,1744060571.897058,3.641268730163574,-8.294182457371357e-14,1744060571.8970597,3.641268730163574,-0.004672595157211377,1744060571.8970606,3.641268730163574,-6.728537025899213e-24,1744060571.8970616,3.641268730163574,10,1744060571.897063,3.641268730163574,0.0,1744060571.897064,3.641268730163574,-22627416989.969524,1744060571.897065,3.641268730163574,0.0,1744060571.8970656,3.641268730163574,28284271247.461903
+1744060571.9169464,3.6612393856048584,-0.03947534816394446,1744060571.9169483,3.6612393856048584,0.004691898128173789,1744060571.9169502,3.6612393856048584,0.0,1744060571.9169524,3.6612393856048584,56568542496.923805,1744060571.9169533,3.6612393856048584,0.0,1744060571.9169545,3.6612393856048584,-8.294182457371357e-14,1744060571.916956,3.6612393856048584,-0.004672595157211377,1744060571.916957,3.6612393856048584,-6.728537025899213e-24,1744060571.916958,3.6612393856048584,10,1744060571.9169593,3.6612393856048584,0.0,1744060571.91696,3.6612393856048584,-22627416989.969524,1744060571.916961,3.6612393856048584,0.0,1744060571.9169621,3.6612393856048584,28284271247.461903
+1744060571.9377258,3.6812379360198975,-0.03947534816394446,1744060571.9377277,3.6812379360198975,0.004691898128173789,1744060571.9377303,3.6812379360198975,0.0,1744060571.9377327,3.6812379360198975,56568542496.923805,1744060571.9377337,3.6812379360198975,0.0,1744060571.9377348,3.6812379360198975,-8.294182457371357e-14,1744060571.9377363,3.6812379360198975,-0.004672595157211377,1744060571.9377372,3.6812379360198975,-6.728537025899213e-24,1744060571.9377387,3.6812379360198975,10,1744060571.93774,3.6812379360198975,0.0,1744060571.9377408,3.6812379360198975,-22627416989.969524,1744060571.9377418,3.6812379360198975,0.0,1744060571.9377432,3.6812379360198975,28284271247.461903
+1744060571.957553,3.7012879848480225,-0.03947534816394446,1744060571.957555,3.7012879848480225,0.004691898128173789,1744060571.957557,3.7012879848480225,0.0,1744060571.957559,3.7012879848480225,56568542496.923805,1744060571.95756,3.7012879848480225,0.0,1744060571.9575613,3.7012879848480225,-8.294182457371357e-14,1744060571.9575624,3.7012879848480225,-0.004672595157211377,1744060571.9575634,3.7012879848480225,-6.728537025899213e-24,1744060571.9575646,3.7012879848480225,10,1744060571.9575658,3.7012879848480225,0.0,1744060571.9575667,3.7012879848480225,-22627416989.969524,1744060571.9575675,3.7012879848480225,0.0,1744060571.9575684,3.7012879848480225,28284271247.461903
+1744060571.9773285,3.721281051635742,-0.03947534816394446,1744060571.9773304,3.721281051635742,0.004691898128173789,1744060571.9773326,3.721281051635742,0.0,1744060571.9773347,3.721281051635742,56568542496.923805,1744060571.9773357,3.721281051635742,0.0,1744060571.977337,3.721281051635742,-8.294182457371357e-14,1744060571.977338,3.721281051635742,-0.004672595157211377,1744060571.977339,3.721281051635742,-6.728537025899213e-24,1744060571.9773405,3.721281051635742,10,1744060571.9773414,3.721281051635742,0.0,1744060571.9773424,3.721281051635742,-22627416989.969524,1744060571.9773436,3.721281051635742,0.0,1744060571.9773445,3.721281051635742,28284271247.461903
+1744060571.9973755,3.74125337600708,-0.03947534816394446,1744060571.997378,3.74125337600708,0.004691898128173789,1744060571.9973824,3.74125337600708,0.0,1744060571.9974089,3.74125337600708,56568542496.923805,1744060571.9974122,3.74125337600708,0.0,1744060571.9974177,3.74125337600708,-8.294182457371357e-14,1744060571.99742,3.74125337600708,-0.004672595157211377,1744060571.9974234,3.74125337600708,-6.728537025899213e-24,1744060571.9974253,3.74125337600708,10,1744060571.9974265,3.74125337600708,0.0,1744060571.9974277,3.74125337600708,-22627416989.969524,1744060571.997429,3.74125337600708,0.0,1744060571.9974303,3.74125337600708,28284271247.461903
+1744060572.0169644,3.7612717151641846,-0.03947534816394446,1744060572.0169663,3.7612717151641846,0.004691898128173789,1744060572.0169685,3.7612717151641846,0.0,1744060572.0169706,3.7612717151641846,56568542496.923805,1744060572.0169718,3.7612717151641846,0.0,1744060572.016973,3.7612717151641846,-8.294182457371357e-14,1744060572.0169744,3.7612717151641846,-0.004672595157211377,1744060572.0169754,3.7612717151641846,-6.728537025899213e-24,1744060572.0169766,3.7612717151641846,10,1744060572.0169773,3.7612717151641846,0.0,1744060572.0169785,3.7612717151641846,-22627416989.969524,1744060572.0169795,3.7612717151641846,0.0,1744060572.0169804,3.7612717151641846,28284271247.461903
+1744060572.036952,3.781235933303833,-0.03947534816394446,1744060572.0369542,3.781235933303833,0.004691898128173789,1744060572.036956,3.781235933303833,0.0,1744060572.0369766,3.781235933303833,56568542496.923805,1744060572.0369778,3.781235933303833,0.0,1744060572.0369792,3.781235933303833,-8.294182457371357e-14,1744060572.0369802,3.781235933303833,-0.004672595157211377,1744060572.0369816,3.781235933303833,-6.728537025899213e-24,1744060572.0369828,3.781235933303833,10,1744060572.0370028,3.781235933303833,0.0,1744060572.0370038,3.781235933303833,-22627416989.969524,1744060572.0370047,3.781235933303833,0.0,1744060572.0370057,3.781235933303833,28284271247.461903
+1744060572.0572193,3.8012399673461914,-0.03947534816394446,1744060572.0572212,3.8012399673461914,0.004691898128173789,1744060572.057223,3.8012399673461914,0.0,1744060572.0572252,3.8012399673461914,56568542496.923805,1744060572.0572262,3.8012399673461914,0.0,1744060572.0572276,3.8012399673461914,-8.294182457371357e-14,1744060572.0572288,3.8012399673461914,-0.004672595157211377,1744060572.05723,3.8012399673461914,-6.728537025899213e-24,1744060572.0572312,3.8012399673461914,10,1744060572.0572321,3.8012399673461914,0.0,1744060572.0572329,3.8012399673461914,-22627416989.969524,1744060572.0572338,3.8012399673461914,0.0,1744060572.0572348,3.8012399673461914,28284271247.461903
+1744060572.0771682,3.8212339878082275,-0.03947534816394446,1744060572.07717,3.8212339878082275,0.004691898128173789,1744060572.0771723,3.8212339878082275,0.0,1744060572.0771744,3.8212339878082275,56568542496.923805,1744060572.0771756,3.8212339878082275,0.0,1744060572.0771768,3.8212339878082275,-8.294182457371357e-14,1744060572.077178,3.8212339878082275,-0.004672595157211377,1744060572.0771794,3.8212339878082275,-6.728537025899213e-24,1744060572.0771809,3.8212339878082275,10,1744060572.077182,3.8212339878082275,0.0,1744060572.077183,3.8212339878082275,-22627416989.969524,1744060572.077184,3.8212339878082275,0.0,1744060572.077185,3.8212339878082275,28284271247.461903
+1744060572.096975,3.8412487506866455,-0.03947534816394446,1744060572.096977,3.8412487506866455,0.004691898128173789,1744060572.0969791,3.8412487506866455,0.0,1744060572.0969815,3.8412487506866455,56568542496.923805,1744060572.0969822,3.8412487506866455,0.0,1744060572.0969837,3.8412487506866455,-8.294182457371357e-14,1744060572.0969849,3.8412487506866455,-0.004672595157211377,1744060572.0969863,3.8412487506866455,-6.728537025899213e-24,1744060572.0969875,3.8412487506866455,10,1744060572.0969884,3.8412487506866455,0.0,1744060572.0969892,3.8412487506866455,-22627416989.969524,1744060572.09699,3.8412487506866455,0.0,1744060572.0969913,3.8412487506866455,28284271247.461903
+1744060572.116912,3.8612582683563232,-0.03947534816394446,1744060572.116914,3.8612582683563232,0.004691898128173789,1744060572.1169167,3.8612582683563232,0.0,1744060572.1169198,3.8612582683563232,56568542496.923805,1744060572.1169217,3.8612582683563232,0.0,1744060572.1169236,3.8612582683563232,-8.294182457371357e-14,1744060572.1169257,3.8612582683563232,-0.004672595157211377,1744060572.1169274,3.8612582683563232,-6.728537025899213e-24,1744060572.1169295,3.8612582683563232,10,1744060572.1169314,3.8612582683563232,0.0,1744060572.116933,3.8612582683563232,-22627416989.969524,1744060572.116935,3.8612582683563232,0.0,1744060572.1169367,3.8612582683563232,28284271247.461903
+1744060572.1369867,3.8812365531921387,-0.03947534816394446,1744060572.1369886,3.8812365531921387,0.004691898128173789,1744060572.1369908,3.8812365531921387,0.0,1744060572.136993,3.8812365531921387,56568542496.923805,1744060572.1369941,3.8812365531921387,0.0,1744060572.136995,3.8812365531921387,-8.294182457371357e-14,1744060572.1369965,3.8812365531921387,-0.004672595157211377,1744060572.1370165,3.8812365531921387,-6.728537025899213e-24,1744060572.137018,3.8812365531921387,10,1744060572.137019,3.8812365531921387,0.0,1744060572.1370199,3.8812365531921387,-22627416989.969524,1744060572.1370208,3.8812365531921387,0.0,1744060572.137022,3.8812365531921387,28284271247.461903
+1744060572.1572855,3.901266574859619,-0.03947534816394446,1744060572.157287,3.901266574859619,0.004691898128173789,1744060572.1572893,3.901266574859619,0.0,1744060572.1572912,3.901266574859619,56568542496.923805,1744060572.1572924,3.901266574859619,0.0,1744060572.1572933,3.901266574859619,-8.294182457371357e-14,1744060572.1572945,3.901266574859619,-0.004672595157211377,1744060572.157296,3.901266574859619,-6.728537025899213e-24,1744060572.157297,3.901266574859619,10,1744060572.1572978,3.901266574859619,0.0,1744060572.157299,3.901266574859619,-22627416989.969524,1744060572.1573,3.901266574859619,0.0,1744060572.157301,3.901266574859619,28284271247.461903
+1744060572.177004,3.921234607696533,-0.03947534816394446,1744060572.177006,3.921234607696533,0.004691898128173789,1744060572.1770082,3.921234607696533,0.0,1744060572.17701,3.921234607696533,56568542496.923805,1744060572.1770113,3.921234607696533,0.0,1744060572.1770122,3.921234607696533,-8.294182457371357e-14,1744060572.1770134,3.921234607696533,-0.004672595157211377,1744060572.1770148,3.921234607696533,-6.728537025899213e-24,1744060572.1770158,3.921234607696533,10,1744060572.1770167,3.921234607696533,0.0,1744060572.177018,3.921234607696533,-22627416989.969524,1744060572.177019,3.921234607696533,0.0,1744060572.1770198,3.921234607696533,28284271247.461903
+1744060572.1970615,3.9412760734558105,-0.03947534816394446,1744060572.1970634,3.9412760734558105,0.004691898128173789,1744060572.1970658,3.9412760734558105,0.0,1744060572.1970677,3.9412760734558105,56568542496.923805,1744060572.1970687,3.9412760734558105,0.0,1744060572.1970701,3.9412760734558105,-8.294182457371357e-14,1744060572.197071,3.9412760734558105,-0.004672595157211377,1744060572.197072,3.9412760734558105,-6.728537025899213e-24,1744060572.1970735,3.9412760734558105,10,1744060572.1970744,3.9412760734558105,0.0,1744060572.1970751,3.9412760734558105,-22627416989.969524,1744060572.1970763,3.9412760734558105,0.0,1744060572.1970773,3.9412760734558105,28284271247.461903
+1744060572.2168887,3.96122670173645,-0.03947534816394446,1744060572.2168903,3.96122670173645,0.004691898128173789,1744060572.2168934,3.96122670173645,0.0,1744060572.2168965,3.96122670173645,56568542496.923805,1744060572.2168982,3.96122670173645,0.0,1744060572.2169,3.96122670173645,-8.294182457371357e-14,1744060572.2169018,3.96122670173645,-0.004672595157211377,1744060572.2169037,3.96122670173645,-6.728537025899213e-24,1744060572.2169058,3.96122670173645,10,1744060572.2169073,3.96122670173645,0.0,1744060572.2169092,3.96122670173645,-22627416989.969524,1744060572.2169101,3.96122670173645,0.0,1744060572.216911,3.96122670173645,28284271247.461903
+1744060572.236989,3.9812846183776855,-0.03947534816394446,1744060572.2369907,3.9812846183776855,0.004691898128173789,1744060572.2369928,3.9812846183776855,0.0,1744060572.2369947,3.9812846183776855,56568542496.923805,1744060572.236996,3.9812846183776855,0.0,1744060572.2369971,3.9812846183776855,-8.294182457371357e-14,1744060572.236998,3.9812846183776855,-0.004672595157211377,1744060572.2369993,3.9812846183776855,-6.728537025899213e-24,1744060572.2370002,3.9812846183776855,10,1744060572.2370017,3.9812846183776855,0.0,1744060572.2370026,3.9812846183776855,-22627416989.969524,1744060572.2370036,3.9812846183776855,0.0,1744060572.2370045,3.9812846183776855,28284271247.461903
+1744060572.257547,4.001253128051758,-0.05610738570857748,1744060572.2575488,4.001253128051758,0.005117367489040554,1744060572.2575512,4.001253128051758,0.0,1744060572.257553,4.001253128051758,56568542496.923805,1744060572.2575543,4.001253128051758,0.0,1744060572.2575555,4.001253128051758,-9.04631313298157e-14,1744060572.2575567,4.001253128051758,-0.005124781785330114,1744060572.257558,4.001253128051758,-7.3796857703389e-24,1744060572.257559,4.001253128051758,10,1744060572.2575603,4.001253128051758,0.0,1744060572.2575614,4.001253128051758,-22627416989.969524,1744060572.2575624,4.001253128051758,0.0,1744060572.2575634,4.001253128051758,28284271247.461903
+1744060572.2772155,4.021302223205566,-0.05610738570857748,1744060572.2772174,4.021302223205566,0.005117367489040554,1744060572.2772195,4.021302223205566,0.0,1744060572.277222,4.021302223205566,56568542496.923805,1744060572.2772229,4.021302223205566,0.0,1744060572.2772243,4.021302223205566,-9.04631313298157e-14,1744060572.2772257,4.021302223205566,-0.005124781785330114,1744060572.277227,4.021302223205566,-7.3796857703389e-24,1744060572.277228,4.021302223205566,10,1744060572.277229,4.021302223205566,0.0,1744060572.27723,4.021302223205566,-22627416989.969524,1744060572.2772312,4.021302223205566,0.0,1744060572.2772322,4.021302223205566,28284271247.461903
+1744060572.2970603,4.041240215301514,-0.05610738570857748,1744060572.2970626,4.041240215301514,0.005117367489040554,1744060572.2970655,4.041240215301514,0.0,1744060572.297068,4.041240215301514,56568542496.923805,1744060572.2970693,4.041240215301514,0.0,1744060572.2970712,4.041240215301514,-9.04631313298157e-14,1744060572.2970726,4.041240215301514,-0.005124781785330114,1744060572.2970738,4.041240215301514,-7.3796857703389e-24,1744060572.2970755,4.041240215301514,10,1744060572.2970767,4.041240215301514,0.0,1744060572.2970781,4.041240215301514,-22627416989.969524,1744060572.2970793,4.041240215301514,0.0,1744060572.2970805,4.041240215301514,28284271247.461903
+1744060572.3170443,4.061269044876099,-0.05610738570857748,1744060572.3170469,4.061269044876099,0.005117367489040554,1744060572.3170493,4.061269044876099,0.0,1744060572.3170524,4.061269044876099,56568542496.923805,1744060572.3170538,4.061269044876099,0.0,1744060572.3170552,4.061269044876099,-9.04631313298157e-14,1744060572.3170567,4.061269044876099,-0.005124781785330114,1744060572.3170583,4.061269044876099,-7.3796857703389e-24,1744060572.3170595,4.061269044876099,10,1744060572.3170612,4.061269044876099,0.0,1744060572.3170624,4.061269044876099,-22627416989.969524,1744060572.3170636,4.061269044876099,0.0,1744060572.317065,4.061269044876099,28284271247.461903
+1744060572.3370764,4.081270217895508,-0.05610738570857748,1744060572.3370788,4.081270217895508,0.005117367489040554,1744060572.3370817,4.081270217895508,0.0,1744060572.3370845,4.081270217895508,56568542496.923805,1744060572.337086,4.081270217895508,0.0,1744060572.3370874,4.081270217895508,-9.04631313298157e-14,1744060572.337089,4.081270217895508,-0.005124781785330114,1744060572.3370907,4.081270217895508,-7.3796857703389e-24,1744060572.3370924,4.081270217895508,10,1744060572.3370936,4.081270217895508,0.0,1744060572.337095,4.081270217895508,-22627416989.969524,1744060572.3370962,4.081270217895508,0.0,1744060572.3370976,4.081270217895508,28284271247.461903
+1744060572.357654,4.101286172866821,-0.05610738570857748,1744060572.3576562,4.101286172866821,0.005117367489040554,1744060572.3576589,4.101286172866821,0.0,1744060572.3576615,4.101286172866821,56568542496.923805,1744060572.3576627,4.101286172866821,0.0,1744060572.3576648,4.101286172866821,-9.04631313298157e-14,1744060572.3576665,4.101286172866821,-0.005124781785330114,1744060572.357668,4.101286172866821,-7.3796857703389e-24,1744060572.3576696,4.101286172866821,10,1744060572.357671,4.101286172866821,0.0,1744060572.3576725,4.101286172866821,-22627416989.969524,1744060572.3576736,4.101286172866821,0.0,1744060572.357675,4.101286172866821,28284271247.461903
+1744060572.3769982,4.121230602264404,-0.05610738570857748,1744060572.3770015,4.121230602264404,0.005117367489040554,1744060572.3770058,4.121230602264404,0.0,1744060572.377009,4.121230602264404,56568542496.923805,1744060572.3770106,4.121230602264404,0.0,1744060572.3770132,4.121230602264404,-9.04631313298157e-14,1744060572.377015,4.121230602264404,-0.005124781785330114,1744060572.377017,4.121230602264404,-7.3796857703389e-24,1744060572.3770192,4.121230602264404,10,1744060572.3770208,4.121230602264404,0.0,1744060572.3770225,4.121230602264404,-22627416989.969524,1744060572.377024,4.121230602264404,0.0,1744060572.3770256,4.121230602264404,28284271247.461903
+1744060572.3970962,4.141274690628052,-0.05610738570857748,1744060572.3970985,4.141274690628052,0.005117367489040554,1744060572.3971014,4.141274690628052,0.0,1744060572.3971045,4.141274690628052,56568542496.923805,1744060572.3971057,4.141274690628052,0.0,1744060572.3971071,4.141274690628052,-9.04631313298157e-14,1744060572.397109,4.141274690628052,-0.005124781785330114,1744060572.3971102,4.141274690628052,-7.3796857703389e-24,1744060572.397112,4.141274690628052,10,1744060572.397113,4.141274690628052,0.0,1744060572.3971143,4.141274690628052,-22627416989.969524,1744060572.3971157,4.141274690628052,0.0,1744060572.397117,4.141274690628052,28284271247.461903
+1744060572.4175224,4.161298990249634,-0.05610738570857748,1744060572.4175255,4.161298990249634,0.005117367489040554,1744060572.4175284,4.161298990249634,0.0,1744060572.4175315,4.161298990249634,56568542496.923805,1744060572.4175327,4.161298990249634,0.0,1744060572.417534,4.161298990249634,-9.04631313298157e-14,1744060572.4175358,4.161298990249634,-0.005124781785330114,1744060572.417537,4.161298990249634,-7.3796857703389e-24,1744060572.417539,4.161298990249634,10,1744060572.4175403,4.161298990249634,0.0,1744060572.4175417,4.161298990249634,-22627416989.969524,1744060572.4175432,4.161298990249634,0.0,1744060572.4175444,4.161298990249634,28284271247.461903
+1744060572.4370778,4.1812379360198975,-0.05610738570857748,1744060572.4370813,4.1812379360198975,0.005117367489040554,1744060572.4370866,4.1812379360198975,0.0,1744060572.4370909,4.1812379360198975,56568542496.923805,1744060572.437093,4.1812379360198975,0.0,1744060572.437096,4.1812379360198975,-9.04631313298157e-14,1744060572.4370985,4.1812379360198975,-0.005124781785330114,1744060572.4371,4.1812379360198975,-7.3796857703389e-24,1744060572.4371016,4.1812379360198975,10,1744060572.4371028,4.1812379360198975,0.0,1744060572.4371042,4.1812379360198975,-22627416989.969524,1744060572.4371052,4.1812379360198975,0.0,1744060572.4371066,4.1812379360198975,28284271247.461903
+1744060572.4576366,4.201259136199951,-0.05610738570857748,1744060572.457639,4.201259136199951,0.005117367489040554,1744060572.4576414,4.201259136199951,0.0,1744060572.4576442,4.201259136199951,56568542496.923805,1744060572.457646,4.201259136199951,0.0,1744060572.4576473,4.201259136199951,-9.04631313298157e-14,1744060572.4576492,4.201259136199951,-0.005124781785330114,1744060572.4576507,4.201259136199951,-7.3796857703389e-24,1744060572.4576523,4.201259136199951,10,1744060572.4576535,4.201259136199951,0.0,1744060572.4576545,4.201259136199951,-22627416989.969524,1744060572.457656,4.201259136199951,0.0,1744060572.457657,4.201259136199951,28284271247.461903
+1744060572.477103,4.221269845962524,-0.05610738570857748,1744060572.4771073,4.221269845962524,0.005117367489040554,1744060572.4771118,4.221269845962524,0.0,1744060572.477116,4.221269845962524,56568542496.923805,1744060572.4771185,4.221269845962524,0.0,1744060572.4771216,4.221269845962524,-9.04631313298157e-14,1744060572.4771242,4.221269845962524,-0.005124781785330114,1744060572.477126,4.221269845962524,-7.3796857703389e-24,1744060572.4771273,4.221269845962524,10,1744060572.477129,4.221269845962524,0.0,1744060572.47713,4.221269845962524,-22627416989.969524,1744060572.4771314,4.221269845962524,0.0,1744060572.4771328,4.221269845962524,28284271247.461903
+1744060572.4971058,4.241279363632202,-0.05610738570857748,1744060572.4971082,4.241279363632202,0.005117367489040554,1744060572.4971108,4.241279363632202,0.0,1744060572.4971137,4.241279363632202,56568542496.923805,1744060572.497115,4.241279363632202,0.0,1744060572.4971163,4.241279363632202,-9.04631313298157e-14,1744060572.497118,4.241279363632202,-0.005124781785330114,1744060572.4971192,4.241279363632202,-7.3796857703389e-24,1744060572.4971209,4.241279363632202,10,1744060572.4971223,4.241279363632202,0.0,1744060572.4971232,4.241279363632202,-22627416989.969524,1744060572.497125,4.241279363632202,0.0,1744060572.497126,4.241279363632202,28284271247.461903
+1744060572.5170732,4.2612621784210205,-0.05610738570857748,1744060572.5170765,4.2612621784210205,0.005117367489040554,1744060572.5170805,4.2612621784210205,0.0,1744060572.5170848,4.2612621784210205,56568542496.923805,1744060572.517087,4.2612621784210205,0.0,1744060572.5170896,4.2612621784210205,-9.04631313298157e-14,1744060572.5170918,4.2612621784210205,-0.005124781785330114,1744060572.517094,4.2612621784210205,-7.3796857703389e-24,1744060572.5170965,4.2612621784210205,10,1744060572.5170987,4.2612621784210205,0.0,1744060572.5171008,4.2612621784210205,-22627416989.969524,1744060572.5171034,4.2612621784210205,0.0,1744060572.5171056,4.2612621784210205,28284271247.461903
+1744060572.537136,4.281281232833862,-0.05610738570857748,1744060572.5371385,4.281281232833862,0.005117367489040554,1744060572.537141,4.281281232833862,0.0,1744060572.5371437,4.281281232833862,56568542496.923805,1744060572.5371451,4.281281232833862,0.0,1744060572.5371466,4.281281232833862,-9.04631313298157e-14,1744060572.5371482,4.281281232833862,-0.005124781785330114,1744060572.5371497,4.281281232833862,-7.3796857703389e-24,1744060572.5371513,4.281281232833862,10,1744060572.5371525,4.281281232833862,0.0,1744060572.5371537,4.281281232833862,-22627416989.969524,1744060572.537155,4.281281232833862,0.0,1744060572.537156,4.281281232833862,28284271247.461903
+1744060572.557646,4.30125880241394,-0.05610738570857748,1744060572.5576484,4.30125880241394,0.005117367489040554,1744060572.557651,4.30125880241394,0.0,1744060572.5576537,4.30125880241394,56568542496.923805,1744060572.5576553,4.30125880241394,0.0,1744060572.557657,4.30125880241394,-9.04631313298157e-14,1744060572.5576587,4.30125880241394,-0.005124781785330114,1744060572.5576599,4.30125880241394,-7.3796857703389e-24,1744060572.5576613,4.30125880241394,10,1744060572.5576627,4.30125880241394,0.0,1744060572.5576637,4.30125880241394,-22627416989.969524,1744060572.557665,4.30125880241394,0.0,1744060572.5576663,4.30125880241394,28284271247.461903
+1744060572.5770612,4.321267604827881,-0.05610738570857748,1744060572.5770638,4.321267604827881,0.005117367489040554,1744060572.5770674,4.321267604827881,0.0,1744060572.5770717,4.321267604827881,56568542496.923805,1744060572.5770738,4.321267604827881,0.0,1744060572.5770767,4.321267604827881,-9.04631313298157e-14,1744060572.5770793,4.321267604827881,-0.005124781785330114,1744060572.5770817,4.321267604827881,-7.3796857703389e-24,1744060572.5770838,4.321267604827881,10,1744060572.577086,4.321267604827881,0.0,1744060572.5770886,4.321267604827881,-22627416989.969524,1744060572.5770905,4.321267604827881,0.0,1744060572.5770931,4.321267604827881,28284271247.461903
+1744060572.5972235,4.341293573379517,-0.05610738570857748,1744060572.5972276,4.341293573379517,0.005117367489040554,1744060572.5972319,4.341293573379517,0.0,1744060572.5972366,4.341293573379517,56568542496.923805,1744060572.597239,4.341293573379517,0.0,1744060572.5972419,4.341293573379517,-9.04631313298157e-14,1744060572.5972443,4.341293573379517,-0.005124781785330114,1744060572.5972466,4.341293573379517,-7.3796857703389e-24,1744060572.5972493,4.341293573379517,10,1744060572.5972517,4.341293573379517,0.0,1744060572.5972536,4.341293573379517,-22627416989.969524,1744060572.5972557,4.341293573379517,0.0,1744060572.597258,4.341293573379517,28284271247.461903
+1744060572.6171036,4.36127233505249,-0.05610738570857748,1744060572.617106,4.36127233505249,0.005117367489040554,1744060572.6171088,4.36127233505249,0.0,1744060572.6171112,4.36127233505249,56568542496.923805,1744060572.6171126,4.36127233505249,0.0,1744060572.617114,4.36127233505249,-9.04631313298157e-14,1744060572.6171157,4.36127233505249,-0.005124781785330114,1744060572.617117,4.36127233505249,-7.3796857703389e-24,1744060572.6171184,4.36127233505249,10,1744060572.6171198,4.36127233505249,0.0,1744060572.6171207,4.36127233505249,-22627416989.969524,1744060572.617122,4.36127233505249,0.0,1744060572.6171234,4.36127233505249,28284271247.461903
+1744060572.6370196,4.381236791610718,-0.05610738570857748,1744060572.6370223,4.381236791610718,0.005117367489040554,1744060572.637025,4.381236791610718,0.0,1744060572.6370275,4.381236791610718,56568542496.923805,1744060572.637029,4.381236791610718,0.0,1744060572.6370304,4.381236791610718,-9.04631313298157e-14,1744060572.637032,4.381236791610718,-0.005124781785330114,1744060572.6370335,4.381236791610718,-7.3796857703389e-24,1744060572.637035,4.381236791610718,10,1744060572.6370363,4.381236791610718,0.0,1744060572.6370375,4.381236791610718,-22627416989.969524,1744060572.637039,4.381236791610718,0.0,1744060572.63704,4.381236791610718,28284271247.461903
+1744060572.657771,4.401314735412598,-0.05610738570857748,1744060572.6577735,4.401314735412598,0.005117367489040554,1744060572.6577764,4.401314735412598,0.0,1744060572.6577792,4.401314735412598,56568542496.923805,1744060572.6577806,4.401314735412598,0.0,1744060572.6577823,4.401314735412598,-9.04631313298157e-14,1744060572.6577837,4.401314735412598,-0.005124781785330114,1744060572.6577854,4.401314735412598,-7.3796857703389e-24,1744060572.6577868,4.401314735412598,10,1744060572.6577883,4.401314735412598,0.0,1744060572.6577895,4.401314735412598,-22627416989.969524,1744060572.6577907,4.401314735412598,0.0,1744060572.6577923,4.401314735412598,28284271247.461903
+1744060572.677034,4.421236038208008,-0.05610738570857748,1744060572.6770363,4.421236038208008,0.005117367489040554,1744060572.6770391,4.421236038208008,0.0,1744060572.6770418,4.421236038208008,56568542496.923805,1744060572.677043,4.421236038208008,0.0,1744060572.6770446,4.421236038208008,-9.04631313298157e-14,1744060572.6770463,4.421236038208008,-0.005124781785330114,1744060572.6770475,4.421236038208008,-7.3796857703389e-24,1744060572.6770492,4.421236038208008,10,1744060572.6770504,4.421236038208008,0.0,1744060572.6770515,4.421236038208008,-22627416989.969524,1744060572.677053,4.421236038208008,0.0,1744060572.6770542,4.421236038208008,28284271247.461903
+1744060572.6971283,4.441272974014282,-0.05610738570857748,1744060572.6971307,4.441272974014282,0.005117367489040554,1744060572.6971333,4.441272974014282,0.0,1744060572.697136,4.441272974014282,56568542496.923805,1744060572.697137,4.441272974014282,0.0,1744060572.697139,4.441272974014282,-9.04631313298157e-14,1744060572.6971405,4.441272974014282,-0.005124781785330114,1744060572.6971424,4.441272974014282,-7.3796857703389e-24,1744060572.6971438,4.441272974014282,10,1744060572.697145,4.441272974014282,0.0,1744060572.6971464,4.441272974014282,-22627416989.969524,1744060572.6971476,4.441272974014282,0.0,1744060572.697149,4.441272974014282,28284271247.461903
+1744060572.7172027,4.461271286010742,-0.05610738570857748,1744060572.7172055,4.461271286010742,0.005117367489040554,1744060572.7172089,4.461271286010742,0.0,1744060572.7172117,4.461271286010742,56568542496.923805,1744060572.717213,4.461271286010742,0.0,1744060572.7172143,4.461271286010742,-9.04631313298157e-14,1744060572.7172163,4.461271286010742,-0.005124781785330114,1744060572.7172182,4.461271286010742,-7.3796857703389e-24,1744060572.7172196,4.461271286010742,10,1744060572.7172208,4.461271286010742,0.0,1744060572.7172222,4.461271286010742,-22627416989.969524,1744060572.7172234,4.461271286010742,0.0,1744060572.717225,4.461271286010742,28284271247.461903
+1744060572.7370687,4.481269121170044,-0.05610738570857748,1744060572.7370708,4.481269121170044,0.005117367489040554,1744060572.7370737,4.481269121170044,0.0,1744060572.7370765,4.481269121170044,56568542496.923805,1744060572.7370777,4.481269121170044,0.0,1744060572.7370794,4.481269121170044,-9.04631313298157e-14,1744060572.737081,4.481269121170044,-0.005124781785330114,1744060572.7370825,4.481269121170044,-7.3796857703389e-24,1744060572.737084,4.481269121170044,10,1744060572.737085,4.481269121170044,0.0,1744060572.7370865,4.481269121170044,-22627416989.969524,1744060572.7370877,4.481269121170044,0.0,1744060572.737089,4.481269121170044,28284271247.461903
+1744060572.7574682,4.501241445541382,-0.06584584303888842,1744060572.7574704,4.501241445541382,0.0016062300492234206,1744060572.757473,4.501241445541382,0.0,1744060572.7574756,4.501241445541382,56568542496.923805,1744060572.7574768,4.501241445541382,0.0,1744060572.7574785,4.501241445541382,-2.839440399775012e-14,1744060572.75748,4.501241445541382,-0.0016077746777509007,1744060572.7574816,4.501241445541382,-2.3151955357921978e-24,1744060572.757483,4.501241445541382,10,1744060572.757484,4.501241445541382,0.0,1744060572.7574854,4.501241445541382,-22627416989.969524,1744060572.7574866,4.501241445541382,0.0,1744060572.7574878,4.501241445541382,28284271247.461903
+1744060572.7770581,4.521238565444946,-0.06584584303888842,1744060572.7770603,4.521238565444946,0.0016062300492234206,1744060572.777063,4.521238565444946,0.0,1744060572.7770658,4.521238565444946,56568542496.923805,1744060572.777067,4.521238565444946,0.0,1744060572.7770686,4.521238565444946,-2.839440399775012e-14,1744060572.77707,4.521238565444946,-0.0016077746777509007,1744060572.7770715,4.521238565444946,-2.3151955357921978e-24,1744060572.777073,4.521238565444946,10,1744060572.777074,4.521238565444946,0.0,1744060572.7770755,4.521238565444946,-22627416989.969524,1744060572.7770767,4.521238565444946,0.0,1744060572.777078,4.521238565444946,28284271247.461903
+1744060572.7971542,4.541247606277466,-0.06584584303888842,1744060572.7971568,4.541247606277466,0.0016062300492234206,1744060572.7971604,4.541247606277466,0.0,1744060572.7971635,4.541247606277466,56568542496.923805,1744060572.7971652,4.541247606277466,0.0,1744060572.7971666,4.541247606277466,-2.839440399775012e-14,1744060572.797168,4.541247606277466,-0.0016077746777509007,1744060572.7971697,4.541247606277466,-2.3151955357921978e-24,1744060572.7971718,4.541247606277466,10,1744060572.7971735,4.541247606277466,0.0,1744060572.7971747,4.541247606277466,-22627416989.969524,1744060572.7971761,4.541247606277466,0.0,1744060572.7971776,4.541247606277466,28284271247.461903
+1744060572.8170195,4.561239719390869,-0.06584584303888842,1744060572.8170216,4.561239719390869,0.0016062300492234206,1744060572.8170242,4.561239719390869,0.0,1744060572.8170273,4.561239719390869,56568542496.923805,1744060572.8170285,4.561239719390869,0.0,1744060572.8170302,4.561239719390869,-2.839440399775012e-14,1744060572.8170316,4.561239719390869,-0.0016077746777509007,1744060572.8170333,4.561239719390869,-2.3151955357921978e-24,1744060572.8170345,4.561239719390869,10,1744060572.8170357,4.561239719390869,0.0,1744060572.817037,4.561239719390869,-22627416989.969524,1744060572.8170383,4.561239719390869,0.0,1744060572.8170397,4.561239719390869,28284271247.461903
+1744060572.8370433,4.581243991851807,-0.06584584303888842,1744060572.8370457,4.581243991851807,0.0016062300492234206,1744060572.8370485,4.581243991851807,0.0,1744060572.8370514,4.581243991851807,56568542496.923805,1744060572.8370526,4.581243991851807,0.0,1744060572.8370545,4.581243991851807,-2.839440399775012e-14,1744060572.837056,4.581243991851807,-0.0016077746777509007,1744060572.8370576,4.581243991851807,-2.3151955357921978e-24,1744060572.8370588,4.581243991851807,10,1744060572.8370602,4.581243991851807,0.0,1744060572.8370614,4.581243991851807,-22627416989.969524,1744060572.8370626,4.581243991851807,0.0,1744060572.837064,4.581243991851807,28284271247.461903
+1744060572.8575497,4.601283073425293,-0.06584584303888842,1744060572.8575518,4.601283073425293,0.0016062300492234206,1744060572.8575547,4.601283073425293,0.0,1744060572.8575575,4.601283073425293,56568542496.923805,1744060572.8575587,4.601283073425293,0.0,1744060572.8575604,4.601283073425293,-2.839440399775012e-14,1744060572.8575618,4.601283073425293,-0.0016077746777509007,1744060572.857563,4.601283073425293,-2.3151955357921978e-24,1744060572.8575647,4.601283073425293,10,1744060572.8575659,4.601283073425293,0.0,1744060572.857567,4.601283073425293,-22627416989.969524,1744060572.8575683,4.601283073425293,0.0,1744060572.8575695,4.601283073425293,28284271247.461903
+1744060572.8771079,4.621240854263306,-0.06584584303888842,1744060572.8771102,4.621240854263306,0.0016062300492234206,1744060572.877113,4.621240854263306,0.0,1744060572.8771157,4.621240854263306,56568542496.923805,1744060572.877117,4.621240854263306,0.0,1744060572.8771183,4.621240854263306,-2.839440399775012e-14,1744060572.8771203,4.621240854263306,-0.0016077746777509007,1744060572.8771214,4.621240854263306,-2.3151955357921978e-24,1744060572.877123,4.621240854263306,10,1744060572.8771243,4.621240854263306,0.0,1744060572.8771257,4.621240854263306,-22627416989.969524,1744060572.877127,4.621240854263306,0.0,1744060572.8771281,4.621240854263306,28284271247.461903
+1744060572.8973982,4.64130711555481,-0.06584584303888842,1744060572.8974016,4.64130711555481,0.0016062300492234206,1744060572.8974051,4.64130711555481,0.0,1744060572.8974087,4.64130711555481,56568542496.923805,1744060572.8974109,4.64130711555481,0.0,1744060572.8974125,4.64130711555481,-2.839440399775012e-14,1744060572.897415,4.64130711555481,-0.0016077746777509007,1744060572.8974166,4.64130711555481,-2.3151955357921978e-24,1744060572.8974197,4.64130711555481,10,1744060572.8974211,4.64130711555481,0.0,1744060572.8974223,4.64130711555481,-22627416989.969524,1744060572.8974245,4.64130711555481,0.0,1744060572.8974264,4.64130711555481,28284271247.461903
+1744060572.9170198,4.661242485046387,-0.06584584303888842,1744060572.9170222,4.661242485046387,0.0016062300492234206,1744060572.917025,4.661242485046387,0.0,1744060572.917028,4.661242485046387,56568542496.923805,1744060572.9170291,4.661242485046387,0.0,1744060572.9170308,4.661242485046387,-2.839440399775012e-14,1744060572.9170325,4.661242485046387,-0.0016077746777509007,1744060572.9170337,4.661242485046387,-2.3151955357921978e-24,1744060572.9170353,4.661242485046387,10,1744060572.9170365,4.661242485046387,0.0,1744060572.9170375,4.661242485046387,-22627416989.969524,1744060572.917039,4.661242485046387,0.0,1744060572.91704,4.661242485046387,28284271247.461903
+1744060572.937091,4.681284427642822,-0.06584584303888842,1744060572.9370937,4.681284427642822,0.0016062300492234206,1744060572.937096,4.681284427642822,0.0,1744060572.937099,4.681284427642822,56568542496.923805,1744060572.9371002,4.681284427642822,0.0,1744060572.937102,4.681284427642822,-2.839440399775012e-14,1744060572.9371033,4.681284427642822,-0.0016077746777509007,1744060572.937105,4.681284427642822,-2.3151955357921978e-24,1744060572.9371064,4.681284427642822,10,1744060572.9371078,4.681284427642822,0.0,1744060572.9371088,4.681284427642822,-22627416989.969524,1744060572.93711,4.681284427642822,0.0,1744060572.9371114,4.681284427642822,28284271247.461903
+1744060572.9575715,4.701241731643677,-0.06584584303888842,1744060572.9575744,4.701241731643677,0.0016062300492234206,1744060572.957577,4.701241731643677,0.0,1744060572.9575799,4.701241731643677,56568542496.923805,1744060572.957581,4.701241731643677,0.0,1744060572.9575825,4.701241731643677,-2.839440399775012e-14,1744060572.9575841,4.701241731643677,-0.0016077746777509007,1744060572.9575856,4.701241731643677,-2.3151955357921978e-24,1744060572.9575872,4.701241731643677,10,1744060572.9575884,4.701241731643677,0.0,1744060572.9575899,4.701241731643677,-22627416989.969524,1744060572.957591,4.701241731643677,0.0,1744060572.957592,4.701241731643677,28284271247.461903
+1744060572.9770238,4.721263885498047,-0.06584584303888842,1744060572.9770262,4.721263885498047,0.0016062300492234206,1744060572.977029,4.721263885498047,0.0,1744060572.9770322,4.721263885498047,56568542496.923805,1744060572.9770334,4.721263885498047,0.0,1744060572.9770353,4.721263885498047,-2.839440399775012e-14,1744060572.9770367,4.721263885498047,-0.0016077746777509007,1744060572.9770384,4.721263885498047,-2.3151955357921978e-24,1744060572.97704,4.721263885498047,10,1744060572.9770415,4.721263885498047,0.0,1744060572.9770427,4.721263885498047,-22627416989.969524,1744060572.9770439,4.721263885498047,0.0,1744060572.977045,4.721263885498047,28284271247.461903
+1744060572.9972346,4.741286516189575,-0.06584584303888842,1744060572.9972374,4.741286516189575,0.0016062300492234206,1744060572.9972408,4.741286516189575,0.0,1744060572.997244,4.741286516189575,56568542496.923805,1744060572.9972456,4.741286516189575,0.0,1744060572.9972472,4.741286516189575,-2.839440399775012e-14,1744060572.9972498,4.741286516189575,-0.0016077746777509007,1744060572.9972515,4.741286516189575,-2.3151955357921978e-24,1744060572.9972532,4.741286516189575,10,1744060572.9972544,4.741286516189575,0.0,1744060572.9972563,4.741286516189575,-22627416989.969524,1744060572.997258,4.741286516189575,0.0,1744060572.9972594,4.741286516189575,28284271247.461903
+1744060573.0170407,4.761235952377319,-0.06584584303888842,1744060573.0170443,4.761235952377319,0.0016062300492234206,1744060573.0170484,4.761235952377319,0.0,1744060573.017052,4.761235952377319,56568542496.923805,1744060573.0170536,4.761235952377319,0.0,1744060573.0170557,4.761235952377319,-2.839440399775012e-14,1744060573.017058,4.761235952377319,-0.0016077746777509007,1744060573.0170598,4.761235952377319,-2.3151955357921978e-24,1744060573.0170617,4.761235952377319,10,1744060573.0170631,4.761235952377319,0.0,1744060573.0170648,4.761235952377319,-22627416989.969524,1744060573.0170665,4.761235952377319,0.0,1744060573.0170684,4.761235952377319,28284271247.461903
+1744060573.037179,4.781301498413086,-0.06584584303888842,1744060573.0371816,4.781301498413086,0.0016062300492234206,1744060573.0371845,4.781301498413086,0.0,1744060573.0371873,4.781301498413086,56568542496.923805,1744060573.0371888,4.781301498413086,0.0,1744060573.0371904,4.781301498413086,-2.839440399775012e-14,1744060573.0371919,4.781301498413086,-0.0016077746777509007,1744060573.0371935,4.781301498413086,-2.3151955357921978e-24,1744060573.037195,4.781301498413086,10,1744060573.0371964,4.781301498413086,0.0,1744060573.0371974,4.781301498413086,-22627416989.969524,1744060573.0371985,4.781301498413086,0.0,1744060573.0372,4.781301498413086,28284271247.461903
+1744060573.0576434,4.801265478134155,-0.06584584303888842,1744060573.0576468,4.801265478134155,0.0016062300492234206,1744060573.0576508,4.801265478134155,0.0,1744060573.0576544,4.801265478134155,56568542496.923805,1744060573.0576558,4.801265478134155,0.0,1744060573.0576582,4.801265478134155,-2.839440399775012e-14,1744060573.0576603,4.801265478134155,-0.0016077746777509007,1744060573.057662,4.801265478134155,-2.3151955357921978e-24,1744060573.0576642,4.801265478134155,10,1744060573.0576663,4.801265478134155,0.0,1744060573.0576677,4.801265478134155,-22627416989.969524,1744060573.0576699,4.801265478134155,0.0,1744060573.057671,4.801265478134155,28284271247.461903
+1744060573.0770316,4.821236610412598,-0.06584584303888842,1744060573.077034,4.821236610412598,0.0016062300492234206,1744060573.0770366,4.821236610412598,0.0,1744060573.0770392,4.821236610412598,56568542496.923805,1744060573.0770407,4.821236610412598,0.0,1744060573.077042,4.821236610412598,-2.839440399775012e-14,1744060573.0770438,4.821236610412598,-0.0016077746777509007,1744060573.0770452,4.821236610412598,-2.3151955357921978e-24,1744060573.0770466,4.821236610412598,10,1744060573.0770478,4.821236610412598,0.0,1744060573.077049,4.821236610412598,-22627416989.969524,1744060573.0770504,4.821236610412598,0.0,1744060573.0770516,4.821236610412598,28284271247.461903
+1744060573.097084,4.8412322998046875,-0.06584584303888842,1744060573.0970874,4.8412322998046875,0.0016062300492234206,1744060573.097092,4.8412322998046875,0.0,1744060573.0970953,4.8412322998046875,56568542496.923805,1744060573.0970972,4.8412322998046875,0.0,1744060573.0970995,4.8412322998046875,-2.839440399775012e-14,1744060573.0971014,4.8412322998046875,-0.0016077746777509007,1744060573.0971034,4.8412322998046875,-2.3151955357921978e-24,1744060573.0971062,4.8412322998046875,10,1744060573.0971084,4.8412322998046875,0.0,1744060573.09711,4.8412322998046875,-22627416989.969524,1744060573.0971117,4.8412322998046875,0.0,1744060573.0971143,4.8412322998046875,28284271247.461903
+1744060573.1171477,4.861277103424072,-0.06584584303888842,1744060573.11715,4.861277103424072,0.0016062300492234206,1744060573.1171527,4.861277103424072,0.0,1744060573.1171556,4.861277103424072,56568542496.923805,1744060573.117157,4.861277103424072,0.0,1744060573.1171587,4.861277103424072,-2.839440399775012e-14,1744060573.1171598,4.861277103424072,-0.0016077746777509007,1744060573.1171615,4.861277103424072,-2.3151955357921978e-24,1744060573.1171627,4.861277103424072,10,1744060573.1171641,4.861277103424072,0.0,1744060573.1171653,4.861277103424072,-22627416989.969524,1744060573.1171665,4.861277103424072,0.0,1744060573.117168,4.861277103424072,28284271247.461903
+1744060573.137068,4.881274461746216,-0.06584584303888842,1744060573.1370704,4.881274461746216,0.0016062300492234206,1744060573.137073,4.881274461746216,0.0,1744060573.137076,4.881274461746216,56568542496.923805,1744060573.1370776,4.881274461746216,0.0,1744060573.137079,4.881274461746216,-2.839440399775012e-14,1744060573.1370807,4.881274461746216,-0.0016077746777509007,1744060573.137082,4.881274461746216,-2.3151955357921978e-24,1744060573.1370833,4.881274461746216,10,1744060573.1370847,4.881274461746216,0.0,1744060573.137086,4.881274461746216,-22627416989.969524,1744060573.1370873,4.881274461746216,0.0,1744060573.1370885,4.881274461746216,28284271247.461903
+1744060573.15748,4.901294708251953,-0.06584584303888842,1744060573.1574821,4.901294708251953,0.0016062300492234206,1744060573.157485,4.901294708251953,0.0,1744060573.1574879,4.901294708251953,56568542496.923805,1744060573.157489,4.901294708251953,0.0,1744060573.1574912,4.901294708251953,-2.839440399775012e-14,1744060573.1574926,4.901294708251953,-0.0016077746777509007,1744060573.1574943,4.901294708251953,-2.3151955357921978e-24,1744060573.1574955,4.901294708251953,10,1744060573.1574972,4.901294708251953,0.0,1744060573.1574981,4.901294708251953,-22627416989.969524,1744060573.1574996,4.901294708251953,0.0,1744060573.1575007,4.901294708251953,28284271247.461903
+1744060573.1770506,4.92127251625061,-0.06584584303888842,1744060573.177053,4.92127251625061,0.0016062300492234206,1744060573.1770556,4.92127251625061,0.0,1744060573.1770582,4.92127251625061,56568542496.923805,1744060573.1770597,4.92127251625061,0.0,1744060573.177061,4.92127251625061,-2.839440399775012e-14,1744060573.1770627,4.92127251625061,-0.0016077746777509007,1744060573.177064,4.92127251625061,-2.3151955357921978e-24,1744060573.1770654,4.92127251625061,10,1744060573.1770668,4.92127251625061,0.0,1744060573.1770678,4.92127251625061,-22627416989.969524,1744060573.177069,4.92127251625061,0.0,1744060573.1770704,4.92127251625061,28284271247.461903
+1744060573.1972694,4.941288232803345,-0.06584584303888842,1744060573.197272,4.941288232803345,0.0016062300492234206,1744060573.1972752,4.941288232803345,0.0,1744060573.1972783,4.941288232803345,56568542496.923805,1744060573.1972795,4.941288232803345,0.0,1744060573.1972811,4.941288232803345,-2.839440399775012e-14,1744060573.197283,4.941288232803345,-0.0016077746777509007,1744060573.1972845,4.941288232803345,-2.3151955357921978e-24,1744060573.1972861,4.941288232803345,10,1744060573.1972873,4.941288232803345,0.0,1744060573.1972888,4.941288232803345,-22627416989.969524,1744060573.1972902,4.941288232803345,0.0,1744060573.1972916,4.941288232803345,28284271247.461903
+1744060573.2170205,4.96123480796814,-0.06584584303888842,1744060573.2170227,4.96123480796814,0.0016062300492234206,1744060573.2170255,4.96123480796814,0.0,1744060573.2170281,4.96123480796814,56568542496.923805,1744060573.2170293,4.96123480796814,0.0,1744060573.2170312,4.96123480796814,-2.839440399775012e-14,1744060573.2170327,4.96123480796814,-0.0016077746777509007,1744060573.2170343,4.96123480796814,-2.3151955357921978e-24,1744060573.2170355,4.96123480796814,10,1744060573.2170367,4.96123480796814,0.0,1744060573.2170382,4.96123480796814,-22627416989.969524,1744060573.2170393,4.96123480796814,0.0,1744060573.2170403,4.96123480796814,28284271247.461903
+1744060573.2370505,4.9812657833099365,-0.06584584303888842,1744060573.2370532,4.9812657833099365,0.0016062300492234206,1744060573.2370558,4.9812657833099365,0.0,1744060573.2370584,4.9812657833099365,56568542496.923805,1744060573.2370596,4.9812657833099365,0.0,1744060573.2370613,4.9812657833099365,-2.839440399775012e-14,1744060573.237063,4.9812657833099365,-0.0016077746777509007,1744060573.2370641,4.9812657833099365,-2.3151955357921978e-24,1744060573.2370658,4.9812657833099365,10,1744060573.237067,4.9812657833099365,0.0,1744060573.2370682,4.9812657833099365,-22627416989.969524,1744060573.2370694,4.9812657833099365,0.0,1744060573.2370706,4.9812657833099365,28284271247.461903
+1744060573.257834,5.001251220703125,-0.07401028308588489,1744060573.2578366,5.001251220703125,-0.0023160842739958117,1744060573.2578392,5.001251220703125,0.0,1744060573.2578418,5.001251220703125,56568542496.923805,1744060573.2578433,5.001251220703125,0.0,1744060573.257845,5.001251220703125,4.094297239704788e-14,1744060573.2578466,5.001251220703125,0.0023160842739958117,1744060573.257848,5.001251220703125,3.3351613543094094e-24,1744060573.2578497,5.001251220703125,10,1744060573.257851,5.001251220703125,0.0,1744060573.257852,5.001251220703125,-22627416989.969524,1744060573.2578537,5.001251220703125,0.0,1744060573.2578554,5.001251220703125,28284271247.461903
+1744060573.2770414,5.021238803863525,-0.07401028308588489,1744060573.2770438,5.021238803863525,-0.0023160842739958117,1744060573.2770462,5.021238803863525,0.0,1744060573.277049,5.021238803863525,56568542496.923805,1744060573.2770503,5.021238803863525,0.0,1744060573.2770522,5.021238803863525,4.094297239704788e-14,1744060573.2770536,5.021238803863525,0.0023160842739958117,1744060573.2770553,5.021238803863525,3.3351613543094094e-24,1744060573.2770565,5.021238803863525,10,1744060573.2770581,5.021238803863525,0.0,1744060573.277059,5.021238803863525,-22627416989.969524,1744060573.2770603,5.021238803863525,0.0,1744060573.2770617,5.021238803863525,28284271247.461903
+1744060573.29702,5.041263580322266,-0.07401028308588489,1744060573.2970219,5.041263580322266,-0.0023160842739958117,1744060573.297024,5.041263580322266,0.0,1744060573.2970264,5.041263580322266,56568542496.923805,1744060573.297027,5.041263580322266,0.0,1744060573.2970283,5.041263580322266,4.094297239704788e-14,1744060573.2970297,5.041263580322266,0.0023160842739958117,1744060573.2970307,5.041263580322266,3.3351613543094094e-24,1744060573.2970316,5.041263580322266,10,1744060573.2970326,5.041263580322266,0.0,1744060573.2970338,5.041263580322266,-22627416989.969524,1744060573.2970345,5.041263580322266,0.0,1744060573.2970355,5.041263580322266,28284271247.461903
+1744060573.3169012,5.061232328414917,-0.07401028308588489,1744060573.3169029,5.061232328414917,-0.0023160842739958117,1744060573.3169048,5.061232328414917,0.0,1744060573.3169067,5.061232328414917,56568542496.923805,1744060573.316908,5.061232328414917,0.0,1744060573.316909,5.061232328414917,4.094297239704788e-14,1744060573.3169103,5.061232328414917,0.0023160842739958117,1744060573.3169115,5.061232328414917,3.3351613543094094e-24,1744060573.3169124,5.061232328414917,10,1744060573.3169134,5.061232328414917,0.0,1744060573.3169143,5.061232328414917,-22627416989.969524,1744060573.3169153,5.061232328414917,0.0,1744060573.3169165,5.061232328414917,28284271247.461903
+1744060573.3369575,5.0812883377075195,-0.07401028308588489,1744060573.3369591,5.0812883377075195,-0.0023160842739958117,1744060573.3369613,5.0812883377075195,0.0,1744060573.3369632,5.0812883377075195,56568542496.923805,1744060573.3369641,5.0812883377075195,0.0,1744060573.3369653,5.0812883377075195,4.094297239704788e-14,1744060573.3369668,5.0812883377075195,0.0023160842739958117,1744060573.3369677,5.0812883377075195,3.3351613543094094e-24,1744060573.3369687,5.0812883377075195,10,1744060573.3369696,5.0812883377075195,0.0,1744060573.3369708,5.0812883377075195,-22627416989.969524,1744060573.3369718,5.0812883377075195,0.0,1744060573.3369727,5.0812883377075195,28284271247.461903
+1744060573.3587787,5.101334810256958,-0.07401028308588489,1744060573.3587823,5.101334810256958,-0.0023160842739958117,1744060573.3587847,5.101334810256958,0.0,1744060573.358787,5.101334810256958,56568542496.923805,1744060573.3588061,5.101334810256958,0.0,1744060573.3588076,5.101334810256958,4.094297239704788e-14,1744060573.3588088,5.101334810256958,0.0023160842739958117,1744060573.3588102,5.101334810256958,3.3351613543094094e-24,1744060573.3588123,5.101334810256958,10,1744060573.3588326,5.101334810256958,0.0,1744060573.3588336,5.101334810256958,-22627416989.969524,1744060573.3588347,5.101334810256958,0.0,1744060573.3588357,5.101334810256958,28284271247.461903
+1744060573.3769765,5.1212687492370605,-0.07401028308588489,1744060573.3769782,5.1212687492370605,-0.0023160842739958117,1744060573.3769805,5.1212687492370605,0.0,1744060573.3769825,5.1212687492370605,56568542496.923805,1744060573.3769836,5.1212687492370605,0.0,1744060573.3769848,5.1212687492370605,4.094297239704788e-14,1744060573.376986,5.1212687492370605,0.0023160842739958117,1744060573.3769877,5.1212687492370605,3.3351613543094094e-24,1744060573.376989,5.1212687492370605,10,1744060573.3769898,5.1212687492370605,0.0,1744060573.376991,5.1212687492370605,-22627416989.969524,1744060573.3769917,5.1212687492370605,0.0,1744060573.3769927,5.1212687492370605,28284271247.461903
+1744060573.396986,5.141268968582153,-0.07401028308588489,1744060573.396988,5.141268968582153,-0.0023160842739958117,1744060573.39699,5.141268968582153,0.0,1744060573.396992,5.141268968582153,56568542496.923805,1744060573.396993,5.141268968582153,0.0,1744060573.3969946,5.141268968582153,4.094297239704788e-14,1744060573.3969955,5.141268968582153,0.0023160842739958117,1744060573.3969965,5.141268968582153,3.3351613543094094e-24,1744060573.396998,5.141268968582153,10,1744060573.3969986,5.141268968582153,0.0,1744060573.3969996,5.141268968582153,-22627416989.969524,1744060573.3970008,5.141268968582153,0.0,1744060573.3970015,5.141268968582153,28284271247.461903
+1744060573.4170885,5.161263942718506,-0.07401028308588489,1744060573.4170907,5.161263942718506,-0.0023160842739958117,1744060573.4170926,5.161263942718506,0.0,1744060573.4170952,5.161263942718506,56568542496.923805,1744060573.4170961,5.161263942718506,0.0,1744060573.4170976,5.161263942718506,4.094297239704788e-14,1744060573.4171226,5.161263942718506,0.0023160842739958117,1744060573.4171247,5.161263942718506,3.3351613543094094e-24,1744060573.4171288,5.161263942718506,10,1744060573.417131,5.161263942718506,0.0,1744060573.4171326,5.161263942718506,-22627416989.969524,1744060573.417134,5.161263942718506,0.0,1744060573.4171357,5.161263942718506,28284271247.461903
+1744060573.4373624,5.181298732757568,-0.07401028308588489,1744060573.4373646,5.181298732757568,-0.0023160842739958117,1744060573.4373667,5.181298732757568,0.0,1744060573.4373689,5.181298732757568,56568542496.923805,1744060573.4373698,5.181298732757568,0.0,1744060573.4373713,5.181298732757568,4.094297239704788e-14,1744060573.4373724,5.181298732757568,0.0023160842739958117,1744060573.4373736,5.181298732757568,3.3351613543094094e-24,1744060573.4373748,5.181298732757568,10,1744060573.4373758,5.181298732757568,0.0,1744060573.4373767,5.181298732757568,-22627416989.969524,1744060573.4373777,5.181298732757568,0.0,1744060573.437379,5.181298732757568,28284271247.461903
+1744060573.4581735,5.201308012008667,-0.07401028308588489,1744060573.458176,5.201308012008667,-0.0023160842739958117,1744060573.4581785,5.201308012008667,0.0,1744060573.4581807,5.201308012008667,56568542496.923805,1744060573.4581816,5.201308012008667,0.0,1744060573.458183,5.201308012008667,4.094297239704788e-14,1744060573.4581845,5.201308012008667,0.0023160842739958117,1744060573.4581857,5.201308012008667,3.3351613543094094e-24,1744060573.458187,5.201308012008667,10,1744060573.4581885,5.201308012008667,0.0,1744060573.4581897,5.201308012008667,-22627416989.969524,1744060573.458191,5.201308012008667,0.0,1744060573.458192,5.201308012008667,28284271247.461903
+1744060573.4768934,5.221234321594238,-0.07401028308588489,1744060573.4768953,5.221234321594238,-0.0023160842739958117,1744060573.4768972,5.221234321594238,0.0,1744060573.4768994,5.221234321594238,56568542496.923805,1744060573.4769003,5.221234321594238,0.0,1744060573.4769013,5.221234321594238,4.094297239704788e-14,1744060573.4769027,5.221234321594238,0.0023160842739958117,1744060573.4769037,5.221234321594238,3.3351613543094094e-24,1744060573.4769046,5.221234321594238,10,1744060573.4769058,5.221234321594238,0.0,1744060573.4769065,5.221234321594238,-22627416989.969524,1744060573.4769075,5.221234321594238,0.0,1744060573.4769084,5.221234321594238,28284271247.461903
+1744060573.4975753,5.241307258605957,-0.07401028308588489,1744060573.4975781,5.241307258605957,-0.0023160842739958117,1744060573.4975822,5.241307258605957,0.0,1744060573.4975867,5.241307258605957,56568542496.923805,1744060573.4975886,5.241307258605957,0.0,1744060573.4975915,5.241307258605957,4.094297239704788e-14,1744060573.4975939,5.241307258605957,0.0023160842739958117,1744060573.4975955,5.241307258605957,3.3351613543094094e-24,1744060573.497598,5.241307258605957,10,1744060573.4975998,5.241307258605957,0.0,1744060573.497602,5.241307258605957,-22627416989.969524,1744060573.4976037,5.241307258605957,0.0,1744060573.4976053,5.241307258605957,28284271247.461903
+1744060573.51691,5.261256456375122,-0.07401028308588489,1744060573.516912,5.261256456375122,-0.0023160842739958117,1744060573.5169141,5.261256456375122,0.0,1744060573.5169163,5.261256456375122,56568542496.923805,1744060573.5169172,5.261256456375122,0.0,1744060573.5169184,5.261256456375122,4.094297239704788e-14,1744060573.5169196,5.261256456375122,0.0023160842739958117,1744060573.5169206,5.261256456375122,3.3351613543094094e-24,1744060573.5169218,5.261256456375122,10,1744060573.516923,5.261256456375122,0.0,1744060573.516924,5.261256456375122,-22627416989.969524,1744060573.5169246,5.261256456375122,0.0,1744060573.5169258,5.261256456375122,28284271247.461903
+1744060573.537485,5.281286239624023,-0.07401028308588489,1744060573.5374873,5.281286239624023,-0.0023160842739958117,1744060573.5374894,5.281286239624023,0.0,1744060573.5374918,5.281286239624023,56568542496.923805,1744060573.5374932,5.281286239624023,0.0,1744060573.537495,5.281286239624023,4.094297239704788e-14,1744060573.537496,5.281286239624023,0.0023160842739958117,1744060573.5374975,5.281286239624023,3.3351613543094094e-24,1744060573.5374992,5.281286239624023,10,1744060573.5375001,5.281286239624023,0.0,1744060573.5375009,5.281286239624023,-22627416989.969524,1744060573.5375023,5.281286239624023,0.0,1744060573.5375032,5.281286239624023,28284271247.461903
+1744060573.5574372,5.301287651062012,-0.07401028308588489,1744060573.5574386,5.301287651062012,-0.0023160842739958117,1744060573.5574408,5.301287651062012,0.0,1744060573.557443,5.301287651062012,56568542496.923805,1744060573.5574436,5.301287651062012,0.0,1744060573.5574448,5.301287651062012,4.094297239704788e-14,1744060573.557446,5.301287651062012,0.0023160842739958117,1744060573.5574472,5.301287651062012,3.3351613543094094e-24,1744060573.5574481,5.301287651062012,10,1744060573.557449,5.301287651062012,0.0,1744060573.55745,5.301287651062012,-22627416989.969524,1744060573.5574512,5.301287651062012,0.0,1744060573.5574522,5.301287651062012,28284271247.461903
+1744060573.576951,5.321255683898926,-0.07401028308588489,1744060573.576953,5.321255683898926,-0.0023160842739958117,1744060573.5769548,5.321255683898926,0.0,1744060573.576957,5.321255683898926,56568542496.923805,1744060573.5769577,5.321255683898926,0.0,1744060573.576959,5.321255683898926,4.094297239704788e-14,1744060573.57696,5.321255683898926,0.0023160842739958117,1744060573.576961,5.321255683898926,3.3351613543094094e-24,1744060573.576962,5.321255683898926,10,1744060573.5769632,5.321255683898926,0.0,1744060573.5769641,5.321255683898926,-22627416989.969524,1744060573.576965,5.321255683898926,0.0,1744060573.5769663,5.321255683898926,28284271247.461903
+1744060573.597447,5.3413214683532715,-0.07401028308588489,1744060573.5974548,5.3413214683532715,-0.0023160842739958117,1744060573.5974576,5.3413214683532715,0.0,1744060573.5974605,5.3413214683532715,56568542496.923805,1744060573.5974617,5.3413214683532715,0.0,1744060573.5974634,5.3413214683532715,4.094297239704788e-14,1744060573.5974646,5.3413214683532715,0.0023160842739958117,1744060573.5974662,5.3413214683532715,3.3351613543094094e-24,1744060573.5974677,5.3413214683532715,10,1744060573.5974686,5.3413214683532715,0.0,1744060573.5974698,5.3413214683532715,-22627416989.969524,1744060573.5974708,5.3413214683532715,0.0,1744060573.5974717,5.3413214683532715,28284271247.461903
+1744060573.6169007,5.361231565475464,-0.07401028308588489,1744060573.6169024,5.361231565475464,-0.0023160842739958117,1744060573.6169047,5.361231565475464,0.0,1744060573.6169066,5.361231565475464,56568542496.923805,1744060573.6169076,5.361231565475464,0.0,1744060573.6169088,5.361231565475464,4.094297239704788e-14,1744060573.6169097,5.361231565475464,0.0023160842739958117,1744060573.616911,5.361231565475464,3.3351613543094094e-24,1744060573.6169121,5.361231565475464,10,1744060573.616913,5.361231565475464,0.0,1744060573.616914,5.361231565475464,-22627416989.969524,1744060573.616915,5.361231565475464,0.0,1744060573.616916,5.361231565475464,28284271247.461903
+1744060573.6371064,5.38126802444458,-0.07401028308588489,1744060573.6371083,5.38126802444458,-0.0023160842739958117,1744060573.6371105,5.38126802444458,0.0,1744060573.6371126,5.38126802444458,56568542496.923805,1744060573.6371136,5.38126802444458,0.0,1744060573.6371148,5.38126802444458,4.094297239704788e-14,1744060573.6371162,5.38126802444458,0.0023160842739958117,1744060573.6371171,5.38126802444458,3.3351613543094094e-24,1744060573.637118,5.38126802444458,10,1744060573.6371193,5.38126802444458,0.0,1744060573.6371202,5.38126802444458,-22627416989.969524,1744060573.6371212,5.38126802444458,0.0,1744060573.6371222,5.38126802444458,28284271247.461903
+1744060573.657282,5.401287078857422,-0.07401028308588489,1744060573.6572838,5.401287078857422,-0.0023160842739958117,1744060573.657286,5.401287078857422,0.0,1744060573.6572878,5.401287078857422,56568542496.923805,1744060573.6572888,5.401287078857422,0.0,1744060573.65729,5.401287078857422,4.094297239704788e-14,1744060573.6572912,5.401287078857422,0.0023160842739958117,1744060573.6572921,5.401287078857422,3.3351613543094094e-24,1744060573.6572933,5.401287078857422,10,1744060573.6572943,5.401287078857422,0.0,1744060573.6572955,5.401287078857422,-22627416989.969524,1744060573.6572962,5.401287078857422,0.0,1744060573.6573124,5.401287078857422,28284271247.461903
+1744060573.6769726,5.421275615692139,-0.07401028308588489,1744060573.6769743,5.421275615692139,-0.0023160842739958117,1744060573.6769764,5.421275615692139,0.0,1744060573.6769783,5.421275615692139,56568542496.923805,1744060573.6769795,5.421275615692139,0.0,1744060573.6769807,5.421275615692139,4.094297239704788e-14,1744060573.676982,5.421275615692139,0.0023160842739958117,1744060573.676983,5.421275615692139,3.3351613543094094e-24,1744060573.676984,5.421275615692139,10,1744060573.676985,5.421275615692139,0.0,1744060573.6769862,5.421275615692139,-22627416989.969524,1744060573.6769872,5.421275615692139,0.0,1744060573.6769881,5.421275615692139,28284271247.461903
+1744060573.6969602,5.441265821456909,-0.07401028308588489,1744060573.696962,5.441265821456909,-0.0023160842739958117,1744060573.6969643,5.441265821456909,0.0,1744060573.6969664,5.441265821456909,56568542496.923805,1744060573.6969671,5.441265821456909,0.0,1744060573.6969686,5.441265821456909,4.094297239704788e-14,1744060573.6969697,5.441265821456909,0.0023160842739958117,1744060573.6969707,5.441265821456909,3.3351613543094094e-24,1744060573.6969721,5.441265821456909,10,1744060573.696973,5.441265821456909,0.0,1744060573.6969738,5.441265821456909,-22627416989.969524,1744060573.6969748,5.441265821456909,0.0,1744060573.696976,5.441265821456909,28284271247.461903
+1744060573.717049,5.461374759674072,-0.07401028308588489,1744060573.7170506,5.461374759674072,-0.0023160842739958117,1744060573.7170527,5.461374759674072,0.0,1744060573.7170546,5.461374759674072,56568542496.923805,1744060573.7170558,5.461374759674072,0.0,1744060573.717057,5.461374759674072,4.094297239704788e-14,1744060573.7170794,5.461374759674072,0.0023160842739958117,1744060573.7170806,5.461374759674072,3.3351613543094094e-24,1744060573.7170818,5.461374759674072,10,1744060573.717083,5.461374759674072,0.0,1744060573.717084,5.461374759674072,-22627416989.969524,1744060573.717085,5.461374759674072,0.0,1744060573.7170858,5.461374759674072,28284271247.461903
+1744060573.7371862,5.4812657833099365,-0.07401028308588489,1744060573.7371893,5.4812657833099365,-0.0023160842739958117,1744060573.7371943,5.4812657833099365,0.0,1744060573.737198,5.4812657833099365,56568542496.923805,1744060573.7372007,5.4812657833099365,0.0,1744060573.7372031,5.4812657833099365,4.094297239704788e-14,1744060573.7372062,5.4812657833099365,0.0023160842739958117,1744060573.7372086,5.4812657833099365,3.3351613543094094e-24,1744060573.737211,5.4812657833099365,10,1744060573.7372136,5.4812657833099365,0.0,1744060573.7372153,5.4812657833099365,-22627416989.969524,1744060573.7372165,5.4812657833099365,0.0,1744060573.737218,5.4812657833099365,28284271247.461903
+1744060573.7571816,5.501263856887817,-0.08118689997072288,1744060573.7571836,5.501263856887817,-0.0017361948963871658,1744060573.7571855,5.501263856887817,0.0,1744060573.7571878,5.501263856887817,56568542496.923805,1744060573.7571888,5.501263856887817,0.0,1744060573.7571902,5.501263856887817,3.0691879616291835e-14,1744060573.7571912,5.501263856887817,0.0017361948963871658,1744060573.7571921,5.501263856887817,2.5001206506135576e-24,1744060573.7571936,5.501263856887817,10,1744060573.7571945,5.501263856887817,0.0,1744060573.7571952,5.501263856887817,-22627416989.969524,1744060573.7571962,5.501263856887817,0.0,1744060573.7571971,5.501263856887817,28284271247.461903
+1744060573.776975,5.521286249160767,-0.08118689997072288,1744060573.7769766,5.521286249160767,-0.0017361948963871658,1744060573.7769787,5.521286249160767,0.0,1744060573.7769806,5.521286249160767,56568542496.923805,1744060573.7769818,5.521286249160767,0.0,1744060573.776983,5.521286249160767,3.0691879616291835e-14,1744060573.776984,5.521286249160767,0.0017361948963871658,1744060573.7769852,5.521286249160767,2.5001206506135576e-24,1744060573.7769864,5.521286249160767,10,1744060573.7769873,5.521286249160767,0.0,1744060573.7769883,5.521286249160767,-22627416989.969524,1744060573.7769892,5.521286249160767,0.0,1744060573.7769902,5.521286249160767,28284271247.461903
+1744060573.7970593,5.541255474090576,-0.08118689997072288,1744060573.7970617,5.541255474090576,-0.0017361948963871658,1744060573.7970638,5.541255474090576,0.0,1744060573.797066,5.541255474090576,56568542496.923805,1744060573.797067,5.541255474090576,0.0,1744060573.797068,5.541255474090576,3.0691879616291835e-14,1744060573.797069,5.541255474090576,0.0017361948963871658,1744060573.7970703,5.541255474090576,2.5001206506135576e-24,1744060573.797072,5.541255474090576,10,1744060573.797073,5.541255474090576,0.0,1744060573.7970736,5.541255474090576,-22627416989.969524,1744060573.7970748,5.541255474090576,0.0,1744060573.7970757,5.541255474090576,28284271247.461903
+1744060573.8169155,5.5612242221832275,-0.08118689997072288,1744060573.8169174,5.5612242221832275,-0.0017361948963871658,1744060573.8169196,5.5612242221832275,0.0,1744060573.8169222,5.5612242221832275,56568542496.923805,1744060573.816923,5.5612242221832275,0.0,1744060573.8169243,5.5612242221832275,3.0691879616291835e-14,1744060573.8169255,5.5612242221832275,0.0017361948963871658,1744060573.8169267,5.5612242221832275,2.5001206506135576e-24,1744060573.8169277,5.5612242221832275,10,1744060573.8169289,5.5612242221832275,0.0,1744060573.8169296,5.5612242221832275,-22627416989.969524,1744060573.8169308,5.5612242221832275,0.0,1744060573.8169317,5.5612242221832275,28284271247.461903
+1744060573.8371046,5.581259489059448,-0.08118689997072288,1744060573.8371065,5.581259489059448,-0.0017361948963871658,1744060573.8371089,5.581259489059448,0.0,1744060573.837111,5.581259489059448,56568542496.923805,1744060573.837112,5.581259489059448,0.0,1744060573.8371134,5.581259489059448,3.0691879616291835e-14,1744060573.8371143,5.581259489059448,0.0017361948963871658,1744060573.8371158,5.581259489059448,2.5001206506135576e-24,1744060573.837117,5.581259489059448,10,1744060573.837118,5.581259489059448,0.0,1744060573.8371189,5.581259489059448,-22627416989.969524,1744060573.83712,5.581259489059448,0.0,1744060573.837121,5.581259489059448,28284271247.461903
+1744060573.8574824,5.601274251937866,-0.08118689997072288,1744060573.8574843,5.601274251937866,-0.0017361948963871658,1744060573.8574865,5.601274251937866,0.0,1744060573.8574889,5.601274251937866,56568542496.923805,1744060573.85749,5.601274251937866,0.0,1744060573.8574913,5.601274251937866,3.0691879616291835e-14,1744060573.8574924,5.601274251937866,0.0017361948963871658,1744060573.857494,5.601274251937866,2.5001206506135576e-24,1744060573.8574953,5.601274251937866,10,1744060573.8574965,5.601274251937866,0.0,1744060573.8574977,5.601274251937866,-22627416989.969524,1744060573.857499,5.601274251937866,0.0,1744060573.8574996,5.601274251937866,28284271247.461903
+1744060573.8774734,5.621296644210815,-0.08118689997072288,1744060573.8774755,5.621296644210815,-0.0017361948963871658,1744060573.877478,5.621296644210815,0.0,1744060573.877481,5.621296644210815,56568542496.923805,1744060573.877507,5.621296644210815,0.0,1744060573.8775094,5.621296644210815,3.0691879616291835e-14,1744060573.8775113,5.621296644210815,0.0017361948963871658,1744060573.8775134,5.621296644210815,2.5001206506135576e-24,1744060573.8775337,5.621296644210815,10,1744060573.8775358,5.621296644210815,0.0,1744060573.877537,5.621296644210815,-22627416989.969524,1744060573.877538,5.621296644210815,0.0,1744060573.8775396,5.621296644210815,28284271247.461903
+1744060573.8972027,5.641258955001831,-0.08118689997072288,1744060573.8972054,5.641258955001831,-0.0017361948963871658,1744060573.897209,5.641258955001831,0.0,1744060573.8972118,5.641258955001831,56568542496.923805,1744060573.8972135,5.641258955001831,0.0,1744060573.897215,5.641258955001831,3.0691879616291835e-14,1744060573.8972166,5.641258955001831,0.0017361948963871658,1744060573.8972187,5.641258955001831,2.5001206506135576e-24,1744060573.8972206,5.641258955001831,10,1744060573.8972232,5.641258955001831,0.0,1744060573.8972256,5.641258955001831,-22627416989.969524,1744060573.897227,5.641258955001831,0.0,1744060573.8972461,5.641258955001831,28284271247.461903
+1744060573.917115,5.661275148391724,-0.08118689997072288,1744060573.9171169,5.661275148391724,-0.0017361948963871658,1744060573.9171193,5.661275148391724,0.0,1744060573.9171216,5.661275148391724,56568542496.923805,1744060573.9171226,5.661275148391724,0.0,1744060573.917124,5.661275148391724,3.0691879616291835e-14,1744060573.9171255,5.661275148391724,0.0017361948963871658,1744060573.9171267,5.661275148391724,2.5001206506135576e-24,1744060573.917128,5.661275148391724,10,1744060573.9171293,5.661275148391724,0.0,1744060573.9171302,5.661275148391724,-22627416989.969524,1744060573.9171314,5.661275148391724,0.0,1744060573.9171326,5.661275148391724,28284271247.461903
+1744060573.936974,5.681284189224243,-0.08118689997072288,1744060573.936976,5.681284189224243,-0.0017361948963871658,1744060573.9369779,5.681284189224243,0.0,1744060573.93698,5.681284189224243,56568542496.923805,1744060573.936981,5.681284189224243,0.0,1744060573.936982,5.681284189224243,3.0691879616291835e-14,1744060573.9369833,5.681284189224243,0.0017361948963871658,1744060573.9369843,5.681284189224243,2.5001206506135576e-24,1744060573.9369855,5.681284189224243,10,1744060573.9369864,5.681284189224243,0.0,1744060573.9369874,5.681284189224243,-22627416989.969524,1744060573.9369884,5.681284189224243,0.0,1744060573.9369895,5.681284189224243,28284271247.461903
+1744060573.9572997,5.701265573501587,-0.08118689997072288,1744060573.9573016,5.701265573501587,-0.0017361948963871658,1744060573.9573035,5.701265573501587,0.0,1744060573.957306,5.701265573501587,56568542496.923805,1744060573.9573069,5.701265573501587,0.0,1744060573.957308,5.701265573501587,3.0691879616291835e-14,1744060573.9573092,5.701265573501587,0.0017361948963871658,1744060573.9573102,5.701265573501587,2.5001206506135576e-24,1744060573.9573114,5.701265573501587,10,1744060573.9573126,5.701265573501587,0.0,1744060573.9573133,5.701265573501587,-22627416989.969524,1744060573.9573143,5.701265573501587,0.0,1744060573.9573154,5.701265573501587,28284271247.461903
+1744060573.9769213,5.721243381500244,-0.08118689997072288,1744060573.9769232,5.721243381500244,-0.0017361948963871658,1744060573.9769251,5.721243381500244,0.0,1744060573.976927,5.721243381500244,56568542496.923805,1744060573.976928,5.721243381500244,0.0,1744060573.9769292,5.721243381500244,3.0691879616291835e-14,1744060573.9769304,5.721243381500244,0.0017361948963871658,1744060573.9769316,5.721243381500244,2.5001206506135576e-24,1744060573.9769325,5.721243381500244,10,1744060573.9769337,5.721243381500244,0.0,1744060573.9769344,5.721243381500244,-22627416989.969524,1744060573.9769356,5.721243381500244,0.0,1744060573.9769363,5.721243381500244,28284271247.461903
+1744060573.9969435,5.741259336471558,-0.08118689997072288,1744060573.9969451,5.741259336471558,-0.0017361948963871658,1744060573.9969475,5.741259336471558,0.0,1744060573.9969494,5.741259336471558,56568542496.923805,1744060573.9969506,5.741259336471558,0.0,1744060573.9969518,5.741259336471558,3.0691879616291835e-14,1744060573.9969528,5.741259336471558,0.0017361948963871658,1744060573.9969542,5.741259336471558,2.5001206506135576e-24,1744060573.9969552,5.741259336471558,10,1744060573.996956,5.741259336471558,0.0,1744060573.9969568,5.741259336471558,-22627416989.969524,1744060573.996958,5.741259336471558,0.0,1744060573.996959,5.741259336471558,28284271247.461903
+1744060574.0171123,5.76126766204834,-0.08118689997072288,1744060574.0171146,5.76126766204834,-0.0017361948963871658,1744060574.0171175,5.76126766204834,0.0,1744060574.0171196,5.76126766204834,56568542496.923805,1744060574.017121,5.76126766204834,0.0,1744060574.0171227,5.76126766204834,3.0691879616291835e-14,1744060574.0171242,5.76126766204834,0.0017361948963871658,1744060574.0171254,5.76126766204834,2.5001206506135576e-24,1744060574.0171266,5.76126766204834,10,1744060574.0171282,5.76126766204834,0.0,1744060574.017129,5.76126766204834,-22627416989.969524,1744060574.0171301,5.76126766204834,0.0,1744060574.0171313,5.76126766204834,28284271247.461903
+1744060574.0369203,5.781240701675415,-0.08118689997072288,1744060574.0369217,5.781240701675415,-0.0017361948963871658,1744060574.0369241,5.781240701675415,0.0,1744060574.0369263,5.781240701675415,56568542496.923805,1744060574.036927,5.781240701675415,0.0,1744060574.0369282,5.781240701675415,3.0691879616291835e-14,1744060574.0369296,5.781240701675415,0.0017361948963871658,1744060574.0369306,5.781240701675415,2.5001206506135576e-24,1744060574.0369318,5.781240701675415,10,1744060574.036933,5.781240701675415,0.0,1744060574.036934,5.781240701675415,-22627416989.969524,1744060574.036935,5.781240701675415,0.0,1744060574.0369363,5.781240701675415,28284271247.461903
+1744060574.0572538,5.801230192184448,-0.08118689997072288,1744060574.0572557,5.801230192184448,-0.0017361948963871658,1744060574.0572574,5.801230192184448,0.0,1744060574.0572598,5.801230192184448,56568542496.923805,1744060574.0572608,5.801230192184448,0.0,1744060574.0572617,5.801230192184448,3.0691879616291835e-14,1744060574.0572634,5.801230192184448,0.0017361948963871658,1744060574.0572643,5.801230192184448,2.5001206506135576e-24,1744060574.0572655,5.801230192184448,10,1744060574.0572665,5.801230192184448,0.0,1744060574.0572674,5.801230192184448,-22627416989.969524,1744060574.0572684,5.801230192184448,0.0,1744060574.0572696,5.801230192184448,28284271247.461903
+1744060574.0770738,5.821271896362305,-0.08118689997072288,1744060574.0770757,5.821271896362305,-0.0017361948963871658,1744060574.0770779,5.821271896362305,0.0,1744060574.0770798,5.821271896362305,56568542496.923805,1744060574.0770807,5.821271896362305,0.0,1744060574.0770822,5.821271896362305,3.0691879616291835e-14,1744060574.0770833,5.821271896362305,0.0017361948963871658,1744060574.0770848,5.821271896362305,2.5001206506135576e-24,1744060574.077086,5.821271896362305,10,1744060574.0770867,5.821271896362305,0.0,1744060574.077088,5.821271896362305,-22627416989.969524,1744060574.077089,5.821271896362305,0.0,1744060574.0770898,5.821271896362305,28284271247.461903
+1744060574.096964,5.841266632080078,-0.08118689997072288,1744060574.0969656,5.841266632080078,-0.0017361948963871658,1744060574.0969677,5.841266632080078,0.0,1744060574.0969698,5.841266632080078,56568542496.923805,1744060574.0969706,5.841266632080078,0.0,1744060574.0969718,5.841266632080078,3.0691879616291835e-14,1744060574.096973,5.841266632080078,0.0017361948963871658,1744060574.0969741,5.841266632080078,2.5001206506135576e-24,1744060574.096975,5.841266632080078,10,1744060574.096976,5.841266632080078,0.0,1744060574.096977,5.841266632080078,-22627416989.969524,1744060574.096978,5.841266632080078,0.0,1744060574.096979,5.841266632080078,28284271247.461903
+1744060574.1169548,5.861265182495117,-0.08118689997072288,1744060574.1169567,5.861265182495117,-0.0017361948963871658,1744060574.1169586,5.861265182495117,0.0,1744060574.1169608,5.861265182495117,56568542496.923805,1744060574.1169617,5.861265182495117,0.0,1744060574.116963,5.861265182495117,3.0691879616291835e-14,1744060574.116964,5.861265182495117,0.0017361948963871658,1744060574.1169653,5.861265182495117,2.5001206506135576e-24,1744060574.1169665,5.861265182495117,10,1744060574.1169674,5.861265182495117,0.0,1744060574.1169682,5.861265182495117,-22627416989.969524,1744060574.116969,5.861265182495117,0.0,1744060574.1169703,5.861265182495117,28284271247.461903
+1744060574.1369295,5.881260633468628,-0.08118689997072288,1744060574.1369317,5.881260633468628,-0.0017361948963871658,1744060574.1369336,5.881260633468628,0.0,1744060574.1369357,5.881260633468628,56568542496.923805,1744060574.1369367,5.881260633468628,0.0,1744060574.136938,5.881260633468628,3.0691879616291835e-14,1744060574.1369393,5.881260633468628,0.0017361948963871658,1744060574.1369405,5.881260633468628,2.5001206506135576e-24,1744060574.1369417,5.881260633468628,10,1744060574.1369426,5.881260633468628,0.0,1744060574.1369436,5.881260633468628,-22627416989.969524,1744060574.1369443,5.881260633468628,0.0,1744060574.1369457,5.881260633468628,28284271247.461903
+1744060574.1580336,5.901301145553589,-0.08118689997072288,1744060574.158036,5.901301145553589,-0.0017361948963871658,1744060574.1580377,5.901301145553589,0.0,1744060574.1580398,5.901301145553589,56568542496.923805,1744060574.1580408,5.901301145553589,0.0,1744060574.1580422,5.901301145553589,3.0691879616291835e-14,1744060574.1580434,5.901301145553589,0.0017361948963871658,1744060574.1580448,5.901301145553589,2.5001206506135576e-24,1744060574.158046,5.901301145553589,10,1744060574.158047,5.901301145553589,0.0,1744060574.1580482,5.901301145553589,-22627416989.969524,1744060574.158049,5.901301145553589,0.0,1744060574.15805,5.901301145553589,28284271247.461903
+1744060574.176998,5.921290397644043,-0.08118689997072288,1744060574.1769996,5.921290397644043,-0.0017361948963871658,1744060574.177002,5.921290397644043,0.0,1744060574.177004,5.921290397644043,56568542496.923805,1744060574.177005,5.921290397644043,0.0,1744060574.1770062,5.921290397644043,3.0691879616291835e-14,1744060574.1770077,5.921290397644043,0.0017361948963871658,1744060574.177009,5.921290397644043,2.5001206506135576e-24,1744060574.1770105,5.921290397644043,10,1744060574.1770115,5.921290397644043,0.0,1744060574.1770124,5.921290397644043,-22627416989.969524,1744060574.1770134,5.921290397644043,0.0,1744060574.1770146,5.921290397644043,28284271247.461903
+1744060574.1970043,5.941274166107178,-0.08118689997072288,1744060574.197006,5.941274166107178,-0.0017361948963871658,1744060574.1970081,5.941274166107178,0.0,1744060574.1970105,5.941274166107178,56568542496.923805,1744060574.1970115,5.941274166107178,0.0,1744060574.1970124,5.941274166107178,3.0691879616291835e-14,1744060574.1970139,5.941274166107178,0.0017361948963871658,1744060574.1970148,5.941274166107178,2.5001206506135576e-24,1744060574.1970158,5.941274166107178,10,1744060574.1970167,5.941274166107178,0.0,1744060574.197018,5.941274166107178,-22627416989.969524,1744060574.1970189,5.941274166107178,0.0,1744060574.1970196,5.941274166107178,28284271247.461903
+1744060574.216939,5.961261987686157,-0.08118689997072288,1744060574.2169416,5.961261987686157,-0.0017361948963871658,1744060574.2169445,5.961261987686157,0.0,1744060574.2169468,5.961261987686157,56568542496.923805,1744060574.2169485,5.961261987686157,0.0,1744060574.2169502,5.961261987686157,3.0691879616291835e-14,1744060574.2169518,5.961261987686157,0.0017361948963871658,1744060574.2169533,5.961261987686157,2.5001206506135576e-24,1744060574.2169552,5.961261987686157,10,1744060574.2169566,5.961261987686157,0.0,1744060574.2169583,5.961261987686157,-22627416989.969524,1744060574.2169597,5.961261987686157,0.0,1744060574.2169616,5.961261987686157,28284271247.461903
+1744060574.2370162,5.9812376499176025,-0.08118689997072288,1744060574.237018,5.9812376499176025,-0.0017361948963871658,1744060574.2370203,5.9812376499176025,0.0,1744060574.2370222,5.9812376499176025,56568542496.923805,1744060574.237023,5.9812376499176025,0.0,1744060574.2370245,5.9812376499176025,3.0691879616291835e-14,1744060574.2370257,5.9812376499176025,0.0017361948963871658,1744060574.237027,5.9812376499176025,2.5001206506135576e-24,1744060574.2370281,5.9812376499176025,10,1744060574.237029,5.9812376499176025,0.0,1744060574.23703,5.9812376499176025,-22627416989.969524,1744060574.237031,5.9812376499176025,0.0,1744060574.237032,5.9812376499176025,28284271247.461903
+1744060574.257941,6.001274108886719,-0.09055178171436956,1744060574.2579434,6.001274108886719,-0.0029533513053594355,1744060574.257946,6.001274108886719,0.0,1744060574.2579484,6.001274108886719,56568542496.923805,1744060574.2579496,6.001274108886719,0.0,1744060574.2579515,6.001274108886719,5.220836837921555e-14,1744060574.257953,6.001274108886719,0.0029533513053594355,1744060574.2579541,6.001274108886719,4.2528258794032514e-24,1744060574.2579556,6.001274108886719,10,1744060574.257957,6.001274108886719,0.0,1744060574.257958,6.001274108886719,-22627416989.969524,1744060574.2579591,6.001274108886719,0.0,1744060574.2579606,6.001274108886719,28284271247.461903
+1744060574.2770278,6.021312475204468,-0.09055178171436956,1744060574.27703,6.021312475204468,-0.0029533513053594355,1744060574.277032,6.021312475204468,0.0,1744060574.277034,6.021312475204468,56568542496.923805,1744060574.277035,6.021312475204468,0.0,1744060574.2770362,6.021312475204468,5.220836837921555e-14,1744060574.2770374,6.021312475204468,0.0029533513053594355,1744060574.2770386,6.021312475204468,4.2528258794032514e-24,1744060574.2770398,6.021312475204468,10,1744060574.277041,6.021312475204468,0.0,1744060574.277042,6.021312475204468,-22627416989.969524,1744060574.2770426,6.021312475204468,0.0,1744060574.2770438,6.021312475204468,28284271247.461903
+1744060574.2969873,6.04128098487854,-0.09055178171436956,1744060574.2969892,6.04128098487854,-0.0029533513053594355,1744060574.2969913,6.04128098487854,0.0,1744060574.2969935,6.04128098487854,56568542496.923805,1744060574.2969944,6.04128098487854,0.0,1744060574.2969959,6.04128098487854,5.220836837921555e-14,1744060574.2969968,6.04128098487854,0.0029533513053594355,1744060574.2969978,6.04128098487854,4.2528258794032514e-24,1744060574.2969992,6.04128098487854,10,1744060574.297,6.04128098487854,0.0,1744060574.297001,6.04128098487854,-22627416989.969524,1744060574.297002,6.04128098487854,0.0,1744060574.2970028,6.04128098487854,28284271247.461903
+1744060574.3169935,6.061241388320923,-0.09055178171436956,1744060574.3169959,6.061241388320923,-0.0029533513053594355,1744060574.3169982,6.061241388320923,0.0,1744060574.3170002,6.061241388320923,56568542496.923805,1744060574.3170009,6.061241388320923,0.0,1744060574.3170023,6.061241388320923,5.220836837921555e-14,1744060574.3170033,6.061241388320923,0.0029533513053594355,1744060574.3170044,6.061241388320923,4.2528258794032514e-24,1744060574.3170056,6.061241388320923,10,1744060574.3170066,6.061241388320923,0.0,1744060574.3170073,6.061241388320923,-22627416989.969524,1744060574.3170085,6.061241388320923,0.0,1744060574.3170094,6.061241388320923,28284271247.461903
+1744060574.3370707,6.081233978271484,-0.09055178171436956,1744060574.337073,6.081233978271484,-0.0029533513053594355,1744060574.3370764,6.081233978271484,0.0,1744060574.3370798,6.081233978271484,56568542496.923805,1744060574.3370817,6.081233978271484,0.0,1744060574.337083,6.081233978271484,5.220836837921555e-14,1744060574.337084,6.081233978271484,0.0029533513053594355,1744060574.3370852,6.081233978271484,4.2528258794032514e-24,1744060574.3370864,6.081233978271484,10,1744060574.3370874,6.081233978271484,0.0,1744060574.3370886,6.081233978271484,-22627416989.969524,1744060574.3370893,6.081233978271484,0.0,1744060574.3370903,6.081233978271484,28284271247.461903
+1744060574.3574247,6.101256847381592,-0.09055178171436956,1744060574.3574266,6.101256847381592,-0.0029533513053594355,1744060574.357429,6.101256847381592,0.0,1744060574.3574314,6.101256847381592,56568542496.923805,1744060574.3574324,6.101256847381592,0.0,1744060574.3574336,6.101256847381592,5.220836837921555e-14,1744060574.357435,6.101256847381592,0.0029533513053594355,1744060574.357436,6.101256847381592,4.2528258794032514e-24,1744060574.3574371,6.101256847381592,10,1744060574.3574383,6.101256847381592,0.0,1744060574.357439,6.101256847381592,-22627416989.969524,1744060574.3574402,6.101256847381592,0.0,1744060574.357441,6.101256847381592,28284271247.461903
+1744060574.3770425,6.121265888214111,-0.09055178171436956,1744060574.3770444,6.121265888214111,-0.0029533513053594355,1744060574.377047,6.121265888214111,0.0,1744060574.3770497,6.121265888214111,56568542496.923805,1744060574.3770509,6.121265888214111,0.0,1744060574.377052,6.121265888214111,5.220836837921555e-14,1744060574.3770537,6.121265888214111,0.0029533513053594355,1744060574.3770547,6.121265888214111,4.2528258794032514e-24,1744060574.3770564,6.121265888214111,10,1744060574.3770576,6.121265888214111,0.0,1744060574.3770585,6.121265888214111,-22627416989.969524,1744060574.3770592,6.121265888214111,0.0,1744060574.377061,6.121265888214111,28284271247.461903
+1744060574.3969848,6.141242980957031,-0.09055178171436956,1744060574.3969865,6.141242980957031,-0.0029533513053594355,1744060574.3969886,6.141242980957031,0.0,1744060574.3969908,6.141242980957031,56568542496.923805,1744060574.3969915,6.141242980957031,0.0,1744060574.396993,6.141242980957031,5.220836837921555e-14,1744060574.396994,6.141242980957031,0.0029533513053594355,1744060574.396995,6.141242980957031,4.2528258794032514e-24,1744060574.3969963,6.141242980957031,10,1744060574.3969975,6.141242980957031,0.0,1744060574.3969982,6.141242980957031,-22627416989.969524,1744060574.3969991,6.141242980957031,0.0,1744060574.397,6.141242980957031,28284271247.461903
+1744060574.417025,6.1612389087677,-0.09055178171436956,1744060574.4170265,6.1612389087677,-0.0029533513053594355,1744060574.4170291,6.1612389087677,0.0,1744060574.417031,6.1612389087677,56568542496.923805,1744060574.4170322,6.1612389087677,0.0,1744060574.4170334,6.1612389087677,5.220836837921555e-14,1744060574.4170349,6.1612389087677,0.0029533513053594355,1744060574.4170358,6.1612389087677,4.2528258794032514e-24,1744060574.417037,6.1612389087677,10,1744060574.417038,6.1612389087677,0.0,1744060574.417039,6.1612389087677,-22627416989.969524,1744060574.4170399,6.1612389087677,0.0,1744060574.4170408,6.1612389087677,28284271247.461903
+1744060574.4374087,6.181376218795776,-0.09055178171436956,1744060574.4374108,6.181376218795776,-0.0029533513053594355,1744060574.4374132,6.181376218795776,0.0,1744060574.4374154,6.181376218795776,56568542496.923805,1744060574.4374166,6.181376218795776,0.0,1744060574.4374354,6.181376218795776,5.220836837921555e-14,1744060574.4374368,6.181376218795776,0.0029533513053594355,1744060574.437438,6.181376218795776,4.2528258794032514e-24,1744060574.4374392,6.181376218795776,10,1744060574.4374409,6.181376218795776,0.0,1744060574.4374416,6.181376218795776,-22627416989.969524,1744060574.4374425,6.181376218795776,0.0,1744060574.4374435,6.181376218795776,28284271247.461903
+1744060574.4574804,6.201256513595581,-0.09055178171436956,1744060574.4574826,6.201256513595581,-0.0029533513053594355,1744060574.4574845,6.201256513595581,0.0,1744060574.457502,6.201256513595581,56568542496.923805,1744060574.4575033,6.201256513595581,0.0,1744060574.4575045,6.201256513595581,5.220836837921555e-14,1744060574.4575055,6.201256513595581,0.0029533513053594355,1744060574.457507,6.201256513595581,4.2528258794032514e-24,1744060574.457508,6.201256513595581,10,1744060574.457509,6.201256513595581,0.0,1744060574.4575102,6.201256513595581,-22627416989.969524,1744060574.4575112,6.201256513595581,0.0,1744060574.4575121,6.201256513595581,28284271247.461903
+1744060574.4769437,6.221252918243408,-0.09055178171436956,1744060574.4769454,6.221252918243408,-0.0029533513053594355,1744060574.4769478,6.221252918243408,0.0,1744060574.47695,6.221252918243408,56568542496.923805,1744060574.476951,6.221252918243408,0.0,1744060574.476952,6.221252918243408,5.220836837921555e-14,1744060574.476953,6.221252918243408,0.0029533513053594355,1744060574.4769545,6.221252918243408,4.2528258794032514e-24,1744060574.4769554,6.221252918243408,10,1744060574.4769564,6.221252918243408,0.0,1744060574.4769573,6.221252918243408,-22627416989.969524,1744060574.4769585,6.221252918243408,0.0,1744060574.4769595,6.221252918243408,28284271247.461903
+1744060574.4971166,6.241239786148071,-0.09055178171436956,1744060574.4971185,6.241239786148071,-0.0029533513053594355,1744060574.4971216,6.241239786148071,0.0,1744060574.4971242,6.241239786148071,56568542496.923805,1744060574.4971251,6.241239786148071,0.0,1744060574.4971263,6.241239786148071,5.220836837921555e-14,1744060574.4971278,6.241239786148071,0.0029533513053594355,1744060574.497129,6.241239786148071,4.2528258794032514e-24,1744060574.4971302,6.241239786148071,10,1744060574.4971316,6.241239786148071,0.0,1744060574.4971323,6.241239786148071,-22627416989.969524,1744060574.4971335,6.241239786148071,0.0,1744060574.497135,6.241239786148071,28284271247.461903
+1744060574.5169115,6.2612316608428955,-0.09055178171436956,1744060574.5169134,6.2612316608428955,-0.0029533513053594355,1744060574.5169156,6.2612316608428955,0.0,1744060574.5169175,6.2612316608428955,56568542496.923805,1744060574.5169184,6.2612316608428955,0.0,1744060574.5169196,6.2612316608428955,5.220836837921555e-14,1744060574.5169208,6.2612316608428955,0.0029533513053594355,1744060574.5169218,6.2612316608428955,4.2528258794032514e-24,1744060574.5169232,6.2612316608428955,10,1744060574.5169241,6.2612316608428955,0.0,1744060574.5169249,6.2612316608428955,-22627416989.969524,1744060574.516926,6.2612316608428955,0.0,1744060574.516927,6.2612316608428955,28284271247.461903
+1744060574.5371072,6.281245946884155,-0.09055178171436956,1744060574.5371103,6.281245946884155,-0.0029533513053594355,1744060574.5371141,6.281245946884155,0.0,1744060574.5371172,6.281245946884155,56568542496.923805,1744060574.5371192,6.281245946884155,0.0,1744060574.537121,6.281245946884155,5.220836837921555e-14,1744060574.5371227,6.281245946884155,0.0029533513053594355,1744060574.5371246,6.281245946884155,4.2528258794032514e-24,1744060574.5371263,6.281245946884155,10,1744060574.537128,6.281245946884155,0.0,1744060574.5371292,6.281245946884155,-22627416989.969524,1744060574.537131,6.281245946884155,0.0,1744060574.5371325,6.281245946884155,28284271247.461903
+1744060574.5574498,6.301262617111206,-0.09055178171436956,1744060574.5574522,6.301262617111206,-0.0029533513053594355,1744060574.5574555,6.301262617111206,0.0,1744060574.5574589,6.301262617111206,56568542496.923805,1744060574.5574608,6.301262617111206,0.0,1744060574.557463,6.301262617111206,5.220836837921555e-14,1744060574.5574648,6.301262617111206,0.0029533513053594355,1744060574.557467,6.301262617111206,4.2528258794032514e-24,1744060574.557469,6.301262617111206,10,1744060574.5574708,6.301262617111206,0.0,1744060574.5574863,6.301262617111206,-22627416989.969524,1744060574.5574882,6.301262617111206,0.0,1744060574.5574899,6.301262617111206,28284271247.461903
+1744060574.5775666,6.321265935897827,-0.09055178171436956,1744060574.5775695,6.321265935897827,-0.0029533513053594355,1744060574.5775728,6.321265935897827,0.0,1744060574.5775762,6.321265935897827,56568542496.923805,1744060574.5775778,6.321265935897827,0.0,1744060574.5775797,6.321265935897827,5.220836837921555e-14,1744060574.577582,6.321265935897827,0.0029533513053594355,1744060574.5775836,6.321265935897827,4.2528258794032514e-24,1744060574.5775857,6.321265935897827,10,1744060574.5775871,6.321265935897827,0.0,1744060574.577589,6.321265935897827,-22627416989.969524,1744060574.577591,6.321265935897827,0.0,1744060574.5775928,6.321265935897827,28284271247.461903
+1744060574.5976033,6.3412487506866455,-0.09055178171436956,1744060574.5976057,6.3412487506866455,-0.0029533513053594355,1744060574.5976086,6.3412487506866455,0.0,1744060574.5976107,6.3412487506866455,56568542496.923805,1744060574.5976121,6.3412487506866455,0.0,1744060574.5976138,6.3412487506866455,5.220836837921555e-14,1744060574.597615,6.3412487506866455,0.0029533513053594355,1744060574.5976162,6.3412487506866455,4.2528258794032514e-24,1744060574.5976174,6.3412487506866455,10,1744060574.5976183,6.3412487506866455,0.0,1744060574.5976195,6.3412487506866455,-22627416989.969524,1744060574.5976205,6.3412487506866455,0.0,1744060574.597622,6.3412487506866455,28284271247.461903
+1744060574.6171625,6.3612658977508545,-0.09055178171436956,1744060574.617165,6.3612658977508545,-0.0029533513053594355,1744060574.6171684,6.3612658977508545,0.0,1744060574.617172,6.3612658977508545,56568542496.923805,1744060574.6171737,6.3612658977508545,0.0,1744060574.617176,6.3612658977508545,5.220836837921555e-14,1744060574.617178,6.3612658977508545,0.0029533513053594355,1744060574.6171799,6.3612658977508545,4.2528258794032514e-24,1744060574.617182,6.3612658977508545,10,1744060574.6171837,6.3612658977508545,0.0,1744060574.6171856,6.3612658977508545,-22627416989.969524,1744060574.6171873,6.3612658977508545,0.0,1744060574.6171896,6.3612658977508545,28284271247.461903
+1744060574.6369734,6.381273508071899,-0.09055178171436956,1744060574.636975,6.381273508071899,-0.0029533513053594355,1744060574.636977,6.381273508071899,0.0,1744060574.636979,6.381273508071899,56568542496.923805,1744060574.6369803,6.381273508071899,0.0,1744060574.6369812,6.381273508071899,5.220836837921555e-14,1744060574.6369824,6.381273508071899,0.0029533513053594355,1744060574.6369836,6.381273508071899,4.2528258794032514e-24,1744060574.636985,6.381273508071899,10,1744060574.636986,6.381273508071899,0.0,1744060574.636987,6.381273508071899,-22627416989.969524,1744060574.636988,6.381273508071899,0.0,1744060574.6369889,6.381273508071899,28284271247.461903
+1744060574.657461,6.401238679885864,-0.09055178171436956,1744060574.6574636,6.401238679885864,-0.0029533513053594355,1744060574.6574664,6.401238679885864,0.0,1744060574.6574702,6.401238679885864,56568542496.923805,1744060574.657472,6.401238679885864,0.0,1744060574.657474,6.401238679885864,5.220836837921555e-14,1744060574.6574762,6.401238679885864,0.0029533513053594355,1744060574.657478,6.401238679885864,4.2528258794032514e-24,1744060574.6574805,6.401238679885864,10,1744060574.6574821,6.401238679885864,0.0,1744060574.657484,6.401238679885864,-22627416989.969524,1744060574.6574857,6.401238679885864,0.0,1744060574.6574876,6.401238679885864,28284271247.461903
+1744060574.6769543,6.42126727104187,-0.09055178171436956,1744060574.6769562,6.42126727104187,-0.0029533513053594355,1744060574.6769586,6.42126727104187,0.0,1744060574.6769607,6.42126727104187,56568542496.923805,1744060574.676962,6.42126727104187,0.0,1744060574.6769629,6.42126727104187,5.220836837921555e-14,1744060574.676964,6.42126727104187,0.0029533513053594355,1744060574.6769652,6.42126727104187,4.2528258794032514e-24,1744060574.6769664,6.42126727104187,10,1744060574.6769674,6.42126727104187,0.0,1744060574.676968,6.42126727104187,-22627416989.969524,1744060574.6769693,6.42126727104187,0.0,1744060574.6769702,6.42126727104187,28284271247.461903
+1744060574.6969886,6.441251039505005,-0.09055178171436956,1744060574.6969905,6.441251039505005,-0.0029533513053594355,1744060574.6969929,6.441251039505005,0.0,1744060574.6969945,6.441251039505005,56568542496.923805,1744060574.6969955,6.441251039505005,0.0,1744060574.696997,6.441251039505005,5.220836837921555e-14,1744060574.6969981,6.441251039505005,0.0029533513053594355,1744060574.696999,6.441251039505005,4.2528258794032514e-24,1744060574.6970007,6.441251039505005,10,1744060574.6970017,6.441251039505005,0.0,1744060574.6970024,6.441251039505005,-22627416989.969524,1744060574.6970036,6.441251039505005,0.0,1744060574.6970046,6.441251039505005,28284271247.461903
+1744060574.7173371,6.461274862289429,-0.09055178171436956,1744060574.717339,6.461274862289429,-0.0029533513053594355,1744060574.7173412,6.461274862289429,0.0,1744060574.7173433,6.461274862289429,56568542496.923805,1744060574.7173443,6.461274862289429,0.0,1744060574.7173455,6.461274862289429,5.220836837921555e-14,1744060574.717347,6.461274862289429,0.0029533513053594355,1744060574.7173479,6.461274862289429,4.2528258794032514e-24,1744060574.717349,6.461274862289429,10,1744060574.7173502,6.461274862289429,0.0,1744060574.7173512,6.461274862289429,-22627416989.969524,1744060574.717352,6.461274862289429,0.0,1744060574.717353,6.461274862289429,28284271247.461903
+1744060574.7369473,6.481235504150391,-0.09055178171436956,1744060574.7369497,6.481235504150391,-0.0029533513053594355,1744060574.736953,6.481235504150391,0.0,1744060574.7369556,6.481235504150391,56568542496.923805,1744060574.7369568,6.481235504150391,0.0,1744060574.7369587,6.481235504150391,5.220836837921555e-14,1744060574.7369602,6.481235504150391,0.0029533513053594355,1744060574.736962,6.481235504150391,4.2528258794032514e-24,1744060574.736964,6.481235504150391,10,1744060574.7369661,6.481235504150391,0.0,1744060574.736967,6.481235504150391,-22627416989.969524,1744060574.7369685,6.481235504150391,0.0,1744060574.7369695,6.481235504150391,28284271247.461903
+1744060574.7572017,6.501227140426636,-0.12754067435524494,1744060574.757203,6.501227140426636,-0.07661067528931714,1744060574.7572052,6.501227140426636,0.0,1744060574.7572074,6.501227140426636,56568542496.923805,1744060574.7572086,6.501227140426636,0.0,1744060574.7572098,6.501227140426636,1.3542982001579854e-12,1744060574.7572112,6.501227140426636,0.07661067528931714,1744060574.7572122,6.501227140426636,1.1031937240831847e-22,1744060574.7572134,6.501227140426636,10,1744060574.7572143,6.501227140426636,0.0,1744060574.7572153,6.501227140426636,-22627416989.969524,1744060574.757216,6.501227140426636,0.0,1744060574.757217,6.501227140426636,28284271247.461903
+1744060574.7770274,6.521317720413208,-0.12754067435524494,1744060574.777029,6.521317720413208,-0.07661067528931714,1744060574.7770312,6.521317720413208,0.0,1744060574.7770333,6.521317720413208,56568542496.923805,1744060574.7770343,6.521317720413208,0.0,1744060574.7770355,6.521317720413208,1.3542982001579854e-12,1744060574.7770364,6.521317720413208,0.07661067528931714,1744060574.777038,6.521317720413208,1.1031937240831847e-22,1744060574.7770393,6.521317720413208,10,1744060574.7770402,6.521317720413208,0.0,1744060574.7770412,6.521317720413208,-22627416989.969524,1744060574.7770422,6.521317720413208,0.0,1744060574.7770429,6.521317720413208,28284271247.461903
+1744060574.797503,6.541239023208618,-0.12754067435524494,1744060574.7975051,6.541239023208618,-0.07661067528931714,1744060574.7975073,6.541239023208618,0.0,1744060574.7975094,6.541239023208618,56568542496.923805,1744060574.7975104,6.541239023208618,0.0,1744060574.7975116,6.541239023208618,1.3542982001579854e-12,1744060574.797513,6.541239023208618,0.07661067528931714,1744060574.7975142,6.541239023208618,1.1031937240831847e-22,1744060574.7975156,6.541239023208618,10,1744060574.7975166,6.541239023208618,0.0,1744060574.7975173,6.541239023208618,-22627416989.969524,1744060574.7975183,6.541239023208618,0.0,1744060574.7975194,6.541239023208618,28284271247.461903
+1744060574.8175888,6.56125545501709,-0.12754067435524494,1744060574.817591,6.56125545501709,-0.07661067528931714,1744060574.8175938,6.56125545501709,0.0,1744060574.8175964,6.56125545501709,56568542496.923805,1744060574.8176246,6.56125545501709,0.0,1744060574.8176267,6.56125545501709,1.3542982001579854e-12,1744060574.8176284,6.56125545501709,0.07661067528931714,1744060574.81763,6.56125545501709,1.1031937240831847e-22,1744060574.8176312,6.56125545501709,10,1744060574.8176322,6.56125545501709,0.0,1744060574.8176334,6.56125545501709,-22627416989.969524,1744060574.8176346,6.56125545501709,0.0,1744060574.8176358,6.56125545501709,28284271247.461903
+1744060574.8369503,6.581234693527222,-0.12754067435524494,1744060574.836952,6.581234693527222,-0.07661067528931714,1744060574.8369544,6.581234693527222,0.0,1744060574.8369565,6.581234693527222,56568542496.923805,1744060574.8369577,6.581234693527222,0.0,1744060574.8369586,6.581234693527222,1.3542982001579854e-12,1744060574.83696,6.581234693527222,0.07661067528931714,1744060574.836961,6.581234693527222,1.1031937240831847e-22,1744060574.8369622,6.581234693527222,10,1744060574.8369637,6.581234693527222,0.0,1744060574.8369644,6.581234693527222,-22627416989.969524,1744060574.8369656,6.581234693527222,0.0,1744060574.8369668,6.581234693527222,28284271247.461903
+1744060574.858044,6.601236343383789,-0.12754067435524494,1744060574.858046,6.601236343383789,-0.07661067528931714,1744060574.8580482,6.601236343383789,0.0,1744060574.8580506,6.601236343383789,56568542496.923805,1744060574.8580515,6.601236343383789,0.0,1744060574.858053,6.601236343383789,1.3542982001579854e-12,1744060574.8580542,6.601236343383789,0.07661067528931714,1744060574.858055,6.601236343383789,1.1031937240831847e-22,1744060574.8580565,6.601236343383789,10,1744060574.8580577,6.601236343383789,0.0,1744060574.8580587,6.601236343383789,-22627416989.969524,1744060574.8580601,6.601236343383789,0.0,1744060574.8580608,6.601236343383789,28284271247.461903
+1744060574.8770795,6.621231317520142,-0.12754067435524494,1744060574.8770816,6.621231317520142,-0.07661067528931714,1744060574.8770835,6.621231317520142,0.0,1744060574.8770854,6.621231317520142,56568542496.923805,1744060574.8770866,6.621231317520142,0.0,1744060574.877088,6.621231317520142,1.3542982001579854e-12,1744060574.8770895,6.621231317520142,0.07661067528931714,1744060574.8770905,6.621231317520142,1.1031937240831847e-22,1744060574.877092,6.621231317520142,10,1744060574.8770926,6.621231317520142,0.0,1744060574.8770936,6.621231317520142,-22627416989.969524,1744060574.8770947,6.621231317520142,0.0,1744060574.8770957,6.621231317520142,28284271247.461903
+1744060574.8970168,6.641259670257568,-0.12754067435524494,1744060574.897019,6.641259670257568,-0.07661067528931714,1744060574.8970208,6.641259670257568,0.0,1744060574.8970232,6.641259670257568,56568542496.923805,1744060574.8970242,6.641259670257568,0.0,1744060574.8970256,6.641259670257568,1.3542982001579854e-12,1744060574.8970265,6.641259670257568,0.07661067528931714,1744060574.8970275,6.641259670257568,1.1031937240831847e-22,1744060574.897029,6.641259670257568,10,1744060574.8970299,6.641259670257568,0.0,1744060574.8970306,6.641259670257568,-22627416989.969524,1744060574.8970318,6.641259670257568,0.0,1744060574.8970327,6.641259670257568,28284271247.461903
+1744060574.916943,6.661231517791748,-0.12754067435524494,1744060574.9169452,6.661231517791748,-0.07661067528931714,1744060574.9169474,6.661231517791748,0.0,1744060574.9169497,6.661231517791748,56568542496.923805,1744060574.9169507,6.661231517791748,0.0,1744060574.9169521,6.661231517791748,1.3542982001579854e-12,1744060574.9169533,6.661231517791748,0.07661067528931714,1744060574.9169543,6.661231517791748,1.1031937240831847e-22,1744060574.9169555,6.661231517791748,10,1744060574.9169564,6.661231517791748,0.0,1744060574.9169574,6.661231517791748,-22627416989.969524,1744060574.916958,6.661231517791748,0.0,1744060574.9169593,6.661231517791748,28284271247.461903
+1744060574.9369135,6.681225061416626,-0.12754067435524494,1744060574.9369152,6.681225061416626,-0.07661067528931714,1744060574.9369173,6.681225061416626,0.0,1744060574.9369192,6.681225061416626,56568542496.923805,1744060574.9369204,6.681225061416626,0.0,1744060574.9369216,6.681225061416626,1.3542982001579854e-12,1744060574.9369226,6.681225061416626,0.07661067528931714,1744060574.9369237,6.681225061416626,1.1031937240831847e-22,1744060574.936925,6.681225061416626,10,1744060574.936926,6.681225061416626,0.0,1744060574.936927,6.681225061416626,-22627416989.969524,1744060574.9369278,6.681225061416626,0.0,1744060574.9369287,6.681225061416626,28284271247.461903
+1744060574.958115,6.701248407363892,-0.12754067435524494,1744060574.958119,6.701248407363892,-0.07661067528931714,1744060574.9581215,6.701248407363892,0.0,1744060574.9581249,6.701248407363892,56568542496.923805,1744060574.9581263,6.701248407363892,0.0,1744060574.958128,6.701248407363892,1.3542982001579854e-12,1744060574.9581294,6.701248407363892,0.07661067528931714,1744060574.9581308,6.701248407363892,1.1031937240831847e-22,1744060574.958133,6.701248407363892,10,1744060574.9581344,6.701248407363892,0.0,1744060574.9581537,6.701248407363892,-22627416989.969524,1744060574.958155,6.701248407363892,0.0,1744060574.9581563,6.701248407363892,28284271247.461903
+1744060574.977103,6.721250772476196,-0.12754067435524494,1744060574.9771051,6.721250772476196,-0.07661067528931714,1744060574.9771073,6.721250772476196,0.0,1744060574.9771092,6.721250772476196,56568542496.923805,1744060574.9771106,6.721250772476196,0.0,1744060574.977112,6.721250772476196,1.3542982001579854e-12,1744060574.977114,6.721250772476196,0.07661067528931714,1744060574.9771156,6.721250772476196,1.1031937240831847e-22,1744060574.9771173,6.721250772476196,10,1744060574.977119,6.721250772476196,0.0,1744060574.9771202,6.721250772476196,-22627416989.969524,1744060574.9771218,6.721250772476196,0.0,1744060574.9771233,6.721250772476196,28284271247.461903
+1744060574.9970021,6.741258144378662,-0.12754067435524494,1744060574.997004,6.741258144378662,-0.07661067528931714,1744060574.9970064,6.741258144378662,0.0,1744060574.9970083,6.741258144378662,56568542496.923805,1744060574.9970098,6.741258144378662,0.0,1744060574.9970107,6.741258144378662,1.3542982001579854e-12,1744060574.997012,6.741258144378662,0.07661067528931714,1744060574.997013,6.741258144378662,1.1031937240831847e-22,1744060574.997014,6.741258144378662,10,1744060574.997015,6.741258144378662,0.0,1744060574.997016,6.741258144378662,-22627416989.969524,1744060574.9970171,6.741258144378662,0.0,1744060574.997018,6.741258144378662,28284271247.461903
+1744060575.0170135,6.761249780654907,-0.12754067435524494,1744060575.0170152,6.761249780654907,-0.07661067528931714,1744060575.0170174,6.761249780654907,0.0,1744060575.0170195,6.761249780654907,56568542496.923805,1744060575.0170205,6.761249780654907,0.0,1744060575.0170217,6.761249780654907,1.3542982001579854e-12,1744060575.0170226,6.761249780654907,0.07661067528931714,1744060575.017024,6.761249780654907,1.1031937240831847e-22,1744060575.017025,6.761249780654907,10,1744060575.017026,6.761249780654907,0.0,1744060575.0170271,6.761249780654907,-22627416989.969524,1744060575.017028,6.761249780654907,0.0,1744060575.017029,6.761249780654907,28284271247.461903
+1744060575.0372727,6.781249523162842,-0.12754067435524494,1744060575.0372746,6.781249523162842,-0.07661067528931714,1744060575.0372772,6.781249523162842,0.0,1744060575.0372791,6.781249523162842,56568542496.923805,1744060575.0372803,6.781249523162842,0.0,1744060575.0372815,6.781249523162842,1.3542982001579854e-12,1744060575.0372827,6.781249523162842,0.07661067528931714,1744060575.037284,6.781249523162842,1.1031937240831847e-22,1744060575.0372849,6.781249523162842,10,1744060575.0372858,6.781249523162842,0.0,1744060575.037287,6.781249523162842,-22627416989.969524,1744060575.0372877,6.781249523162842,0.0,1744060575.0372887,6.781249523162842,28284271247.461903
+1744060575.0582464,6.801284074783325,-0.12754067435524494,1744060575.058249,6.801284074783325,-0.07661067528931714,1744060575.0582514,6.801284074783325,0.0,1744060575.0582535,6.801284074783325,56568542496.923805,1744060575.0582545,6.801284074783325,0.0,1744060575.0582561,6.801284074783325,1.3542982001579854e-12,1744060575.0582573,6.801284074783325,0.07661067528931714,1744060575.0582588,6.801284074783325,1.1031937240831847e-22,1744060575.0582602,6.801284074783325,10,1744060575.0582612,6.801284074783325,0.0,1744060575.0582623,6.801284074783325,-22627416989.969524,1744060575.0582633,6.801284074783325,0.0,1744060575.0582643,6.801284074783325,28284271247.461903
+1744060575.077042,6.8212339878082275,-0.12754067435524494,1744060575.077044,6.8212339878082275,-0.07661067528931714,1744060575.077046,6.8212339878082275,0.0,1744060575.0770483,6.8212339878082275,56568542496.923805,1744060575.0770493,6.8212339878082275,0.0,1744060575.0770504,6.8212339878082275,1.3542982001579854e-12,1744060575.0770516,6.8212339878082275,0.07661067528931714,1744060575.0770526,6.8212339878082275,1.1031937240831847e-22,1744060575.0770538,6.8212339878082275,10,1744060575.0770547,6.8212339878082275,0.0,1744060575.0770557,6.8212339878082275,-22627416989.969524,1744060575.077057,6.8212339878082275,0.0,1744060575.0770578,6.8212339878082275,28284271247.461903
+1744060575.0980144,6.8417017459869385,-0.12754067435524494,1744060575.0980165,6.8417017459869385,-0.07661067528931714,1744060575.0980194,6.8417017459869385,0.0,1744060575.0980222,6.8417017459869385,56568542496.923805,1744060575.0980237,6.8417017459869385,0.0,1744060575.0980256,6.8417017459869385,1.3542982001579854e-12,1744060575.0980268,6.8417017459869385,0.07661067528931714,1744060575.098028,6.8417017459869385,1.1031937240831847e-22,1744060575.0980294,6.8417017459869385,10,1744060575.0980303,6.8417017459869385,0.0,1744060575.0980313,6.8417017459869385,-22627416989.969524,1744060575.0980327,6.8417017459869385,0.0,1744060575.0980337,6.8417017459869385,28284271247.461903
+1744060575.1169455,6.8612377643585205,-0.12754067435524494,1744060575.1169472,6.8612377643585205,-0.07661067528931714,1744060575.1169496,6.8612377643585205,0.0,1744060575.1169517,6.8612377643585205,56568542496.923805,1744060575.116953,6.8612377643585205,0.0,1744060575.116954,6.8612377643585205,1.3542982001579854e-12,1744060575.116955,6.8612377643585205,0.07661067528931714,1744060575.1169562,6.8612377643585205,1.1031937240831847e-22,1744060575.1169572,6.8612377643585205,10,1744060575.1169581,6.8612377643585205,0.0,1744060575.116959,6.8612377643585205,-22627416989.969524,1744060575.11696,6.8612377643585205,0.0,1744060575.116961,6.8612377643585205,28284271247.461903
+1744060575.1370552,6.881249189376831,-0.12754067435524494,1744060575.137057,6.881249189376831,-0.07661067528931714,1744060575.1370597,6.881249189376831,0.0,1744060575.1370616,6.881249189376831,56568542496.923805,1744060575.1370625,6.881249189376831,0.0,1744060575.137064,6.881249189376831,1.3542982001579854e-12,1744060575.137065,6.881249189376831,0.07661067528931714,1744060575.1370661,6.881249189376831,1.1031937240831847e-22,1744060575.1370673,6.881249189376831,10,1744060575.1370683,6.881249189376831,0.0,1744060575.137069,6.881249189376831,-22627416989.969524,1744060575.1370707,6.881249189376831,0.0,1744060575.1370716,6.881249189376831,28284271247.461903
+1744060575.1572428,6.9012534618377686,-0.12754067435524494,1744060575.1572444,6.9012534618377686,-0.07661067528931714,1744060575.1572464,6.9012534618377686,0.0,1744060575.1572485,6.9012534618377686,56568542496.923805,1744060575.1572495,6.9012534618377686,0.0,1744060575.1572506,6.9012534618377686,1.3542982001579854e-12,1744060575.1572518,6.9012534618377686,0.07661067528931714,1744060575.1572528,6.9012534618377686,1.1031937240831847e-22,1744060575.1572542,6.9012534618377686,10,1744060575.1572552,6.9012534618377686,0.0,1744060575.157256,6.9012534618377686,-22627416989.969524,1744060575.1572568,6.9012534618377686,0.0,1744060575.1572578,6.9012534618377686,28284271247.461903
+1744060575.1773071,6.921260118484497,-0.12754067435524494,1744060575.1773129,6.921260118484497,-0.07661067528931714,1744060575.1773162,6.921260118484497,0.0,1744060575.1773195,6.921260118484497,56568542496.923805,1744060575.1773212,6.921260118484497,0.0,1744060575.1773233,6.921260118484497,1.3542982001579854e-12,1744060575.177325,6.921260118484497,0.07661067528931714,1744060575.1773276,6.921260118484497,1.1031937240831847e-22,1744060575.17733,6.921260118484497,10,1744060575.1773317,6.921260118484497,0.0,1744060575.1773334,6.921260118484497,-22627416989.969524,1744060575.177335,6.921260118484497,0.0,1744060575.177337,6.921260118484497,28284271247.461903
+1744060575.1970174,6.941226959228516,-0.12754067435524494,1744060575.1970198,6.941226959228516,-0.07661067528931714,1744060575.1970227,6.941226959228516,0.0,1744060575.1970253,6.941226959228516,56568542496.923805,1744060575.1970274,6.941226959228516,0.0,1744060575.1970294,6.941226959228516,1.3542982001579854e-12,1744060575.1970315,6.941226959228516,0.07661067528931714,1744060575.1970334,6.941226959228516,1.1031937240831847e-22,1744060575.1970348,6.941226959228516,10,1744060575.1970367,6.941226959228516,0.0,1744060575.1970384,6.941226959228516,-22627416989.969524,1744060575.1970396,6.941226959228516,0.0,1744060575.1970408,6.941226959228516,28284271247.461903
+1744060575.216948,6.961238145828247,-0.12754067435524494,1744060575.21695,6.961238145828247,-0.07661067528931714,1744060575.216952,6.961238145828247,0.0,1744060575.216954,6.961238145828247,56568542496.923805,1744060575.2169552,6.961238145828247,0.0,1744060575.2169564,6.961238145828247,1.3542982001579854e-12,1744060575.2169578,6.961238145828247,0.07661067528931714,1744060575.2169588,6.961238145828247,1.1031937240831847e-22,1744060575.2169597,6.961238145828247,10,1744060575.2169607,6.961238145828247,0.0,1744060575.2169619,6.961238145828247,-22627416989.969524,1744060575.2169628,6.961238145828247,0.0,1744060575.2169635,6.961238145828247,28284271247.461903
+1744060575.2381794,6.981348037719727,-0.12754067435524494,1744060575.2381833,6.981348037719727,-0.07661067528931714,1744060575.238204,6.981348037719727,0.0,1744060575.2382088,6.981348037719727,56568542496.923805,1744060575.238229,6.981348037719727,0.0,1744060575.238231,6.981348037719727,1.3542982001579854e-12,1744060575.2382326,6.981348037719727,0.07661067528931714,1744060575.2382345,6.981348037719727,1.1031937240831847e-22,1744060575.2382367,6.981348037719727,10,1744060575.2382379,6.981348037719727,0.0,1744060575.2382395,6.981348037719727,-22627416989.969524,1744060575.238241,6.981348037719727,0.0,1744060575.238243,6.981348037719727,28284271247.461903
+1744060575.2573485,7.001244306564331,-0.24277197195257105,1744060575.2573507,7.001244306564331,-0.5539993048037981,1744060575.2573526,7.001244306564331,0.0,1744060575.2573547,7.001244306564331,56568542496.923805,1744060575.2573557,7.001244306564331,0.0,1744060575.2573571,7.001244306564331,9.793416629596688e-12,1744060575.2573583,7.001244306564331,0.5539993048037981,1744060575.2573593,7.001244306564331,7.9775899885421165e-22,1744060575.2573605,7.001244306564331,10,1744060575.2573614,7.001244306564331,0.0,1744060575.2573621,7.001244306564331,-22627416989.969524,1744060575.257363,7.001244306564331,0.0,1744060575.257364,7.001244306564331,28284271247.461903
+1744060575.276977,7.021228313446045,-0.24277197195257105,1744060575.2769797,7.021228313446045,-0.5539993048037981,1744060575.2769828,7.021228313446045,0.0,1744060575.2769854,7.021228313446045,56568542496.923805,1744060575.2769864,7.021228313446045,0.0,1744060575.2769878,7.021228313446045,9.793416629596688e-12,1744060575.2769892,7.021228313446045,0.5539993048037981,1744060575.276991,7.021228313446045,7.9775899885421165e-22,1744060575.2769926,7.021228313446045,10,1744060575.2769935,7.021228313446045,0.0,1744060575.2769942,7.021228313446045,-22627416989.969524,1744060575.276996,7.021228313446045,0.0,1744060575.276997,7.021228313446045,28284271247.461903
+1744060575.2974224,7.041349411010742,-0.24277197195257105,1744060575.2974243,7.041349411010742,-0.5539993048037981,1744060575.297427,7.041349411010742,0.0,1744060575.297429,7.041349411010742,56568542496.923805,1744060575.2974303,7.041349411010742,0.0,1744060575.2974315,7.041349411010742,9.793416629596688e-12,1744060575.297433,7.041349411010742,0.5539993048037981,1744060575.297434,7.041349411010742,7.9775899885421165e-22,1744060575.2974353,7.041349411010742,10,1744060575.2974365,7.041349411010742,0.0,1744060575.2974374,7.041349411010742,-22627416989.969524,1744060575.2974384,7.041349411010742,0.0,1744060575.2974396,7.041349411010742,28284271247.461903
+1744060575.31691,7.061231374740601,-0.24277197195257105,1744060575.316912,7.061231374740601,-0.5539993048037981,1744060575.316914,7.061231374740601,0.0,1744060575.3169172,7.061231374740601,56568542496.923805,1744060575.316919,7.061231374740601,0.0,1744060575.3169208,7.061231374740601,9.793416629596688e-12,1744060575.3169227,7.061231374740601,0.5539993048037981,1744060575.3169239,7.061231374740601,7.9775899885421165e-22,1744060575.3169248,7.061231374740601,10,1744060575.316926,7.061231374740601,0.0,1744060575.316927,7.061231374740601,-22627416989.969524,1744060575.3169277,7.061231374740601,0.0,1744060575.3169289,7.061231374740601,28284271247.461903
+1744060575.336958,7.081242322921753,-0.24277197195257105,1744060575.3369598,7.081242322921753,-0.5539993048037981,1744060575.3369617,7.081242322921753,0.0,1744060575.336964,7.081242322921753,56568542496.923805,1744060575.336965,7.081242322921753,0.0,1744060575.3369665,7.081242322921753,9.793416629596688e-12,1744060575.3369675,7.081242322921753,0.5539993048037981,1744060575.3369687,7.081242322921753,7.9775899885421165e-22,1744060575.33697,7.081242322921753,10,1744060575.336971,7.081242322921753,0.0,1744060575.336972,7.081242322921753,-22627416989.969524,1744060575.3369734,7.081242322921753,0.0,1744060575.3369744,7.081242322921753,28284271247.461903
+1744060575.3572087,7.101227760314941,-0.24277197195257105,1744060575.3572106,7.101227760314941,-0.5539993048037981,1744060575.3572123,7.101227760314941,0.0,1744060575.3572145,7.101227760314941,56568542496.923805,1744060575.3572154,7.101227760314941,0.0,1744060575.3572166,7.101227760314941,9.793416629596688e-12,1744060575.3572178,7.101227760314941,0.5539993048037981,1744060575.3572187,7.101227760314941,7.9775899885421165e-22,1744060575.35722,7.101227760314941,10,1744060575.3572211,7.101227760314941,0.0,1744060575.3572218,7.101227760314941,-22627416989.969524,1744060575.3572228,7.101227760314941,0.0,1744060575.357224,7.101227760314941,28284271247.461903
+1744060575.3771045,7.121276140213013,-0.24277197195257105,1744060575.3771067,7.121276140213013,-0.5539993048037981,1744060575.377109,7.121276140213013,0.0,1744060575.3771112,7.121276140213013,56568542496.923805,1744060575.3771124,7.121276140213013,0.0,1744060575.3771136,7.121276140213013,9.793416629596688e-12,1744060575.3771148,7.121276140213013,0.5539993048037981,1744060575.3771162,7.121276140213013,7.9775899885421165e-22,1744060575.3771174,7.121276140213013,10,1744060575.3771183,7.121276140213013,0.0,1744060575.3771195,7.121276140213013,-22627416989.969524,1744060575.3771205,7.121276140213013,0.0,1744060575.3771217,7.121276140213013,28284271247.461903
+1744060575.3970807,7.141249656677246,-0.24277197195257105,1744060575.3970826,7.141249656677246,-0.5539993048037981,1744060575.397085,7.141249656677246,0.0,1744060575.3970873,7.141249656677246,56568542496.923805,1744060575.3970883,7.141249656677246,0.0,1744060575.3970895,7.141249656677246,9.793416629596688e-12,1744060575.397091,7.141249656677246,0.5539993048037981,1744060575.397092,7.141249656677246,7.9775899885421165e-22,1744060575.397093,7.141249656677246,10,1744060575.3970942,7.141249656677246,0.0,1744060575.3970952,7.141249656677246,-22627416989.969524,1744060575.3970964,7.141249656677246,0.0,1744060575.3970976,7.141249656677246,28284271247.461903
+1744060575.4169395,7.161238193511963,-0.24277197195257105,1744060575.4169414,7.161238193511963,-0.5539993048037981,1744060575.4169438,7.161238193511963,0.0,1744060575.4169464,7.161238193511963,56568542496.923805,1744060575.4169474,7.161238193511963,0.0,1744060575.4169488,7.161238193511963,9.793416629596688e-12,1744060575.41695,7.161238193511963,0.5539993048037981,1744060575.416951,7.161238193511963,7.9775899885421165e-22,1744060575.4169524,7.161238193511963,10,1744060575.4169533,7.161238193511963,0.0,1744060575.4169543,7.161238193511963,-22627416989.969524,1744060575.416956,7.161238193511963,0.0,1744060575.416957,7.161238193511963,28284271247.461903
+1744060575.4372985,7.181257724761963,-0.24277197195257105,1744060575.4373019,7.181257724761963,-0.5539993048037981,1744060575.4373043,7.181257724761963,0.0,1744060575.437307,7.181257724761963,56568542496.923805,1744060575.4373095,7.181257724761963,0.0,1744060575.4373114,7.181257724761963,9.793416629596688e-12,1744060575.4373136,7.181257724761963,0.5539993048037981,1744060575.4373248,7.181257724761963,7.9775899885421165e-22,1744060575.4373276,7.181257724761963,10,1744060575.437329,7.181257724761963,0.0,1744060575.4373305,7.181257724761963,-22627416989.969524,1744060575.437332,7.181257724761963,0.0,1744060575.4373336,7.181257724761963,28284271247.461903
+1744060575.4578242,7.201247692108154,-0.24277197195257105,1744060575.4578273,7.201247692108154,-0.5539993048037981,1744060575.457831,7.201247692108154,0.0,1744060575.4578345,7.201247692108154,56568542496.923805,1744060575.4578364,7.201247692108154,0.0,1744060575.4578385,7.201247692108154,9.793416629596688e-12,1744060575.4578404,7.201247692108154,0.5539993048037981,1744060575.4578424,7.201247692108154,7.9775899885421165e-22,1744060575.4578445,7.201247692108154,10,1744060575.4578462,7.201247692108154,0.0,1744060575.457848,7.201247692108154,-22627416989.969524,1744060575.4578502,7.201247692108154,0.0,1744060575.457852,7.201247692108154,28284271247.461903
+1744060575.4769988,7.22123646736145,-0.24277197195257105,1744060575.4770007,7.22123646736145,-0.5539993048037981,1744060575.477003,7.22123646736145,0.0,1744060575.477005,7.22123646736145,56568542496.923805,1744060575.4770062,7.22123646736145,0.0,1744060575.4770074,7.22123646736145,9.793416629596688e-12,1744060575.4770086,7.22123646736145,0.5539993048037981,1744060575.47701,7.22123646736145,7.9775899885421165e-22,1744060575.477011,7.22123646736145,10,1744060575.477012,7.22123646736145,0.0,1744060575.477013,7.22123646736145,-22627416989.969524,1744060575.4770143,7.22123646736145,0.0,1744060575.4770153,7.22123646736145,28284271247.461903
+1744060575.496993,7.241230726242065,-0.24277197195257105,1744060575.496995,7.241230726242065,-0.5539993048037981,1744060575.4969974,7.241230726242065,0.0,1744060575.4969997,7.241230726242065,56568542496.923805,1744060575.4970007,7.241230726242065,0.0,1744060575.497002,7.241230726242065,9.793416629596688e-12,1744060575.4970033,7.241230726242065,0.5539993048037981,1744060575.4970043,7.241230726242065,7.9775899885421165e-22,1744060575.4970055,7.241230726242065,10,1744060575.4970067,7.241230726242065,0.0,1744060575.4970076,7.241230726242065,-22627416989.969524,1744060575.4970086,7.241230726242065,0.0,1744060575.49701,7.241230726242065,28284271247.461903
+1744060575.5169625,7.261235475540161,-0.24277197195257105,1744060575.5169647,7.261235475540161,-0.5539993048037981,1744060575.5169666,7.261235475540161,0.0,1744060575.5169687,7.261235475540161,56568542496.923805,1744060575.5169697,7.261235475540161,0.0,1744060575.5169713,7.261235475540161,9.793416629596688e-12,1744060575.5169725,7.261235475540161,0.5539993048037981,1744060575.5169735,7.261235475540161,7.9775899885421165e-22,1744060575.516975,7.261235475540161,10,1744060575.5169759,7.261235475540161,0.0,1744060575.5169768,7.261235475540161,-22627416989.969524,1744060575.516978,7.261235475540161,0.0,1744060575.516979,7.261235475540161,28284271247.461903
+1744060575.5369709,7.281233072280884,-0.24277197195257105,1744060575.536973,7.281233072280884,-0.5539993048037981,1744060575.5369751,7.281233072280884,0.0,1744060575.536977,7.281233072280884,56568542496.923805,1744060575.5369782,7.281233072280884,0.0,1744060575.5369794,7.281233072280884,9.793416629596688e-12,1744060575.5369806,7.281233072280884,0.5539993048037981,1744060575.5369818,7.281233072280884,7.9775899885421165e-22,1744060575.536983,7.281233072280884,10,1744060575.536984,7.281233072280884,0.0,1744060575.5369852,7.281233072280884,-22627416989.969524,1744060575.536986,7.281233072280884,0.0,1744060575.536987,7.281233072280884,28284271247.461903
+1744060575.5579042,7.301244497299194,-0.24277197195257105,1744060575.5579078,7.301244497299194,-0.5539993048037981,1744060575.557912,7.301244497299194,0.0,1744060575.5579162,7.301244497299194,56568542496.923805,1744060575.5579183,7.301244497299194,0.0,1744060575.5579207,7.301244497299194,9.793416629596688e-12,1744060575.5579236,7.301244497299194,0.5539993048037981,1744060575.5579257,7.301244497299194,7.9775899885421165e-22,1744060575.5579276,7.301244497299194,10,1744060575.5579298,7.301244497299194,0.0,1744060575.5579321,7.301244497299194,-22627416989.969524,1744060575.5579345,7.301244497299194,0.0,1744060575.5579364,7.301244497299194,28284271247.461903
+1744060575.577018,7.321225166320801,-0.24277197195257105,1744060575.5770206,7.321225166320801,-0.5539993048037981,1744060575.5770237,7.321225166320801,0.0,1744060575.5770266,7.321225166320801,56568542496.923805,1744060575.577028,7.321225166320801,0.0,1744060575.5770302,7.321225166320801,9.793416629596688e-12,1744060575.5770316,7.321225166320801,0.5539993048037981,1744060575.5770335,7.321225166320801,7.9775899885421165e-22,1744060575.577035,7.321225166320801,10,1744060575.5770366,7.321225166320801,0.0,1744060575.5770378,7.321225166320801,-22627416989.969524,1744060575.5770397,7.321225166320801,0.0,1744060575.5770414,7.321225166320801,28284271247.461903
+1744060575.5970314,7.341279745101929,-0.24277197195257105,1744060575.5970333,7.341279745101929,-0.5539993048037981,1744060575.5970354,7.341279745101929,0.0,1744060575.5970376,7.341279745101929,56568542496.923805,1744060575.5970385,7.341279745101929,0.0,1744060575.59704,7.341279745101929,9.793416629596688e-12,1744060575.597041,7.341279745101929,0.5539993048037981,1744060575.597042,7.341279745101929,7.9775899885421165e-22,1744060575.5970433,7.341279745101929,10,1744060575.5970442,7.341279745101929,0.0,1744060575.597045,7.341279745101929,-22627416989.969524,1744060575.5970464,7.341279745101929,0.0,1744060575.597047,7.341279745101929,28284271247.461903
+1744060575.6174688,7.361258506774902,-0.24277197195257105,1744060575.6174717,7.361258506774902,-0.5539993048037981,1744060575.6174748,7.361258506774902,0.0,1744060575.6174781,7.361258506774902,56568542496.923805,1744060575.6174796,7.361258506774902,0.0,1744060575.6174815,7.361258506774902,9.793416629596688e-12,1744060575.6174834,7.361258506774902,0.5539993048037981,1744060575.6174855,7.361258506774902,7.9775899885421165e-22,1744060575.6174874,7.361258506774902,10,1744060575.617489,7.361258506774902,0.0,1744060575.6174908,7.361258506774902,-22627416989.969524,1744060575.6174922,7.361258506774902,0.0,1744060575.617494,7.361258506774902,28284271247.461903
+1744060575.636961,7.381265163421631,-0.24277197195257105,1744060575.636963,7.381265163421631,-0.5539993048037981,1744060575.6369648,7.381265163421631,0.0,1744060575.636967,7.381265163421631,56568542496.923805,1744060575.636968,7.381265163421631,0.0,1744060575.6369693,7.381265163421631,9.793416629596688e-12,1744060575.6369703,7.381265163421631,0.5539993048037981,1744060575.6369715,7.381265163421631,7.9775899885421165e-22,1744060575.6369724,7.381265163421631,10,1744060575.6369736,7.381265163421631,0.0,1744060575.6369743,7.381265163421631,-22627416989.969524,1744060575.6369753,7.381265163421631,0.0,1744060575.6369765,7.381265163421631,28284271247.461903
+1744060575.6573277,7.401233434677124,-0.24277197195257105,1744060575.6573296,7.401233434677124,-0.5539993048037981,1744060575.6573317,7.401233434677124,0.0,1744060575.6573339,7.401233434677124,56568542496.923805,1744060575.6573348,7.401233434677124,0.0,1744060575.657336,7.401233434677124,9.793416629596688e-12,1744060575.6573372,7.401233434677124,0.5539993048037981,1744060575.6573381,7.401233434677124,7.9775899885421165e-22,1744060575.6573393,7.401233434677124,10,1744060575.65734,7.401233434677124,0.0,1744060575.6573412,7.401233434677124,-22627416989.969524,1744060575.6573422,7.401233434677124,0.0,1744060575.6573431,7.401233434677124,28284271247.461903
+1744060575.6769888,7.421230316162109,-0.24277197195257105,1744060575.6769907,7.421230316162109,-0.5539993048037981,1744060575.6769931,7.421230316162109,0.0,1744060575.676995,7.421230316162109,56568542496.923805,1744060575.6769965,7.421230316162109,0.0,1744060575.6769977,7.421230316162109,9.793416629596688e-12,1744060575.6769989,7.421230316162109,0.5539993048037981,1744060575.677,7.421230316162109,7.9775899885421165e-22,1744060575.6770012,7.421230316162109,10,1744060575.6770022,7.421230316162109,0.0,1744060575.677003,7.421230316162109,-22627416989.969524,1744060575.677004,7.421230316162109,0.0,1744060575.677005,7.421230316162109,28284271247.461903
+1744060575.6970296,7.441229343414307,-0.24277197195257105,1744060575.6970317,7.441229343414307,-0.5539993048037981,1744060575.697034,7.441229343414307,0.0,1744060575.697036,7.441229343414307,56568542496.923805,1744060575.697037,7.441229343414307,0.0,1744060575.6970384,7.441229343414307,9.793416629596688e-12,1744060575.6970394,7.441229343414307,0.5539993048037981,1744060575.6970406,7.441229343414307,7.9775899885421165e-22,1744060575.6970417,7.441229343414307,10,1744060575.6970427,7.441229343414307,0.0,1744060575.6970437,7.441229343414307,-22627416989.969524,1744060575.6970448,7.441229343414307,0.0,1744060575.6970458,7.441229343414307,28284271247.461903
+1744060575.7169352,7.461232900619507,-0.24277197195257105,1744060575.7169366,7.461232900619507,-0.5539993048037981,1744060575.716939,7.461232900619507,0.0,1744060575.716941,7.461232900619507,56568542496.923805,1744060575.7169418,7.461232900619507,0.0,1744060575.7169433,7.461232900619507,9.793416629596688e-12,1744060575.7169447,7.461232900619507,0.5539993048037981,1744060575.7169456,7.461232900619507,7.9775899885421165e-22,1744060575.7169466,7.461232900619507,10,1744060575.7169478,7.461232900619507,0.0,1744060575.7169487,7.461232900619507,-22627416989.969524,1744060575.7169497,7.461232900619507,0.0,1744060575.7169511,7.461232900619507,28284271247.461903
+1744060575.7371943,7.481276273727417,-0.24277197195257105,1744060575.737196,7.481276273727417,-0.5539993048037981,1744060575.737198,7.481276273727417,0.0,1744060575.7372,7.481276273727417,56568542496.923805,1744060575.7372012,7.481276273727417,0.0,1744060575.7372024,7.481276273727417,9.793416629596688e-12,1744060575.7372034,7.481276273727417,0.5539993048037981,1744060575.7372046,7.481276273727417,7.9775899885421165e-22,1744060575.7372055,7.481276273727417,10,1744060575.7372065,7.481276273727417,0.0,1744060575.7372077,7.481276273727417,-22627416989.969524,1744060575.7372086,7.481276273727417,0.0,1744060575.7372093,7.481276273727417,28284271247.461903
+1744060575.7573373,7.501230478286743,-0.5329950211469685,1744060575.7573392,7.501230478286743,-1.630700955924497,1744060575.7573411,7.501230478286743,0.0,1744060575.7573435,7.501230478286743,56568542496.923805,1744060575.7573445,7.501230478286743,0.0,1744060575.7573457,7.501230478286743,2.8826992599249125e-11,1744060575.757347,7.501230478286743,1.630700955924497,1744060575.7573485,7.501230478286743,2.3482093763209815e-21,1744060575.75735,7.501230478286743,10,1744060575.757351,7.501230478286743,0.0,1744060575.7573519,7.501230478286743,-22627416989.969524,1744060575.7573526,7.501230478286743,0.0,1744060575.7573538,7.501230478286743,28284271247.461903
+1744060575.777198,7.521276950836182,-0.5329950211469685,1744060575.7772,7.521276950836182,-1.630700955924497,1744060575.7772021,7.521276950836182,0.0,1744060575.7772043,7.521276950836182,56568542496.923805,1744060575.7772052,7.521276950836182,0.0,1744060575.777207,7.521276950836182,2.8826992599249125e-11,1744060575.7772083,7.521276950836182,1.630700955924497,1744060575.7772093,7.521276950836182,2.3482093763209815e-21,1744060575.7772107,7.521276950836182,10,1744060575.7772117,7.521276950836182,0.0,1744060575.7772124,7.521276950836182,-22627416989.969524,1744060575.7772133,7.521276950836182,0.0,1744060575.7772145,7.521276950836182,28284271247.461903
+1744060575.7973866,7.541265249252319,-0.5329950211469685,1744060575.7973888,7.541265249252319,-1.630700955924497,1744060575.7973912,7.541265249252319,0.0,1744060575.7973933,7.541265249252319,56568542496.923805,1744060575.7973948,7.541265249252319,0.0,1744060575.797396,7.541265249252319,2.8826992599249125e-11,1744060575.7973979,7.541265249252319,1.630700955924497,1744060575.797399,7.541265249252319,2.3482093763209815e-21,1744060575.7974,7.541265249252319,10,1744060575.7974012,7.541265249252319,0.0,1744060575.7974021,7.541265249252319,-22627416989.969524,1744060575.797403,7.541265249252319,0.0,1744060575.797404,7.541265249252319,28284271247.461903
+1744060575.816992,7.561283588409424,-0.5329950211469685,1744060575.8169937,7.561283588409424,-1.630700955924497,1744060575.8169959,7.561283588409424,0.0,1744060575.816998,7.561283588409424,56568542496.923805,1744060575.816999,7.561283588409424,0.0,1744060575.8170002,7.561283588409424,2.8826992599249125e-11,1744060575.817001,7.561283588409424,1.630700955924497,1744060575.8170025,7.561283588409424,2.3482093763209815e-21,1744060575.8170035,7.561283588409424,10,1744060575.8170044,7.561283588409424,0.0,1744060575.8170054,7.561283588409424,-22627416989.969524,1744060575.8170063,7.561283588409424,0.0,1744060575.8170073,7.561283588409424,28284271247.461903
+1744060575.8372784,7.5812389850616455,-0.5329950211469685,1744060575.8372808,7.5812389850616455,-1.630700955924497,1744060575.837283,7.5812389850616455,0.0,1744060575.8372848,7.5812389850616455,56568542496.923805,1744060575.837286,7.5812389850616455,0.0,1744060575.8372872,7.5812389850616455,2.8826992599249125e-11,1744060575.8372884,7.5812389850616455,1.630700955924497,1744060575.8372898,7.5812389850616455,2.3482093763209815e-21,1744060575.8372908,7.5812389850616455,10,1744060575.837292,7.5812389850616455,0.0,1744060575.8372931,7.5812389850616455,-22627416989.969524,1744060575.837294,7.5812389850616455,0.0,1744060575.8372953,7.5812389850616455,28284271247.461903
+1744060575.8574345,7.601232290267944,-0.5329950211469685,1744060575.8574367,7.601232290267944,-1.630700955924497,1744060575.857439,7.601232290267944,0.0,1744060575.857441,7.601232290267944,56568542496.923805,1744060575.8574421,7.601232290267944,0.0,1744060575.8574433,7.601232290267944,2.8826992599249125e-11,1744060575.8574445,7.601232290267944,1.630700955924497,1744060575.8574457,7.601232290267944,2.3482093763209815e-21,1744060575.8574467,7.601232290267944,10,1744060575.857448,7.601232290267944,0.0,1744060575.8574493,7.601232290267944,-22627416989.969524,1744060575.8574502,7.601232290267944,0.0,1744060575.8574512,7.601232290267944,28284271247.461903
+1744060575.8771136,7.621261358261108,-0.5329950211469685,1744060575.8771157,7.621261358261108,-1.630700955924497,1744060575.8771179,7.621261358261108,0.0,1744060575.87712,7.621261358261108,56568542496.923805,1744060575.8771212,7.621261358261108,0.0,1744060575.8771226,7.621261358261108,2.8826992599249125e-11,1744060575.8771238,7.621261358261108,1.630700955924497,1744060575.8771248,7.621261358261108,2.3482093763209815e-21,1744060575.8771262,7.621261358261108,10,1744060575.8771274,7.621261358261108,0.0,1744060575.8771281,7.621261358261108,-22627416989.969524,1744060575.8771296,7.621261358261108,0.0,1744060575.8771305,7.621261358261108,28284271247.461903
+1744060575.8969479,7.641228199005127,-0.5329950211469685,1744060575.89695,7.641228199005127,-1.630700955924497,1744060575.8969522,7.641228199005127,0.0,1744060575.8969543,7.641228199005127,56568542496.923805,1744060575.8969555,7.641228199005127,0.0,1744060575.8969567,7.641228199005127,2.8826992599249125e-11,1744060575.8969579,7.641228199005127,1.630700955924497,1744060575.896959,7.641228199005127,2.3482093763209815e-21,1744060575.89696,7.641228199005127,10,1744060575.896961,7.641228199005127,0.0,1744060575.8969617,7.641228199005127,-22627416989.969524,1744060575.8969631,7.641228199005127,0.0,1744060575.8969638,7.641228199005127,28284271247.461903
+1744060575.9170866,7.66126823425293,-0.5329950211469685,1744060575.9170885,7.66126823425293,-1.630700955924497,1744060575.9170907,7.66126823425293,0.0,1744060575.9170926,7.66126823425293,56568542496.923805,1744060575.9170933,7.66126823425293,0.0,1744060575.9170947,7.66126823425293,2.8826992599249125e-11,1744060575.917096,7.66126823425293,1.630700955924497,1744060575.9170969,7.66126823425293,2.3482093763209815e-21,1744060575.9170983,7.66126823425293,10,1744060575.9170992,7.66126823425293,0.0,1744060575.9171,7.66126823425293,-22627416989.969524,1744060575.9171011,7.66126823425293,0.0,1744060575.917102,7.66126823425293,28284271247.461903
+1744060575.9370675,7.681234836578369,-0.5329950211469685,1744060575.93707,7.681234836578369,-1.630700955924497,1744060575.937072,7.681234836578369,0.0,1744060575.9370742,7.681234836578369,56568542496.923805,1744060575.9370754,7.681234836578369,0.0,1744060575.9370768,7.681234836578369,2.8826992599249125e-11,1744060575.9370782,7.681234836578369,1.630700955924497,1744060575.9370797,7.681234836578369,2.3482093763209815e-21,1744060575.9370809,7.681234836578369,10,1744060575.937082,7.681234836578369,0.0,1744060575.9370832,7.681234836578369,-22627416989.969524,1744060575.9370842,7.681234836578369,0.0,1744060575.9370854,7.681234836578369,28284271247.461903
+1744060575.9571867,7.701250791549683,-0.5329950211469685,1744060575.9571886,7.701250791549683,-1.630700955924497,1744060575.9571908,7.701250791549683,0.0,1744060575.957193,7.701250791549683,56568542496.923805,1744060575.9571943,7.701250791549683,0.0,1744060575.9571955,7.701250791549683,2.8826992599249125e-11,1744060575.9571967,7.701250791549683,1.630700955924497,1744060575.9571981,7.701250791549683,2.3482093763209815e-21,1744060575.957199,7.701250791549683,10,1744060575.9572,7.701250791549683,0.0,1744060575.9572012,7.701250791549683,-22627416989.969524,1744060575.9572022,7.701250791549683,0.0,1744060575.957203,7.701250791549683,28284271247.461903
+1744060575.9770336,7.721262216567993,-0.5329950211469685,1744060575.9770355,7.721262216567993,-1.630700955924497,1744060575.9770377,7.721262216567993,0.0,1744060575.9770396,7.721262216567993,56568542496.923805,1744060575.9770405,7.721262216567993,0.0,1744060575.977042,7.721262216567993,2.8826992599249125e-11,1744060575.977043,7.721262216567993,1.630700955924497,1744060575.977044,7.721262216567993,2.3482093763209815e-21,1744060575.9770453,7.721262216567993,10,1744060575.9770463,7.721262216567993,0.0,1744060575.9770472,7.721262216567993,-22627416989.969524,1744060575.9770484,7.721262216567993,0.0,1744060575.977049,7.721262216567993,28284271247.461903
+1744060575.9969203,7.741254091262817,-0.5329950211469685,1744060575.996922,7.741254091262817,-1.630700955924497,1744060575.9969242,7.741254091262817,0.0,1744060575.9969263,7.741254091262817,56568542496.923805,1744060575.9969273,7.741254091262817,0.0,1744060575.9969282,7.741254091262817,2.8826992599249125e-11,1744060575.9969296,7.741254091262817,1.630700955924497,1744060575.9969306,7.741254091262817,2.3482093763209815e-21,1744060575.9969318,7.741254091262817,10,1744060575.9969325,7.741254091262817,0.0,1744060575.9969337,7.741254091262817,-22627416989.969524,1744060575.9969347,7.741254091262817,0.0,1744060575.9969394,7.741254091262817,28284271247.461903
+1744060576.016957,7.761262655258179,-0.5329950211469685,1744060576.0169587,7.761262655258179,-1.630700955924497,1744060576.0169609,7.761262655258179,0.0,1744060576.0169628,7.761262655258179,56568542496.923805,1744060576.016964,7.761262655258179,0.0,1744060576.0169652,7.761262655258179,2.8826992599249125e-11,1744060576.0169663,7.761262655258179,1.630700955924497,1744060576.0169675,7.761262655258179,2.3482093763209815e-21,1744060576.0169685,7.761262655258179,10,1744060576.0169694,7.761262655258179,0.0,1744060576.0169702,7.761262655258179,-22627416989.969524,1744060576.0169713,7.761262655258179,0.0,1744060576.0169723,7.761262655258179,28284271247.461903
+1744060576.0370405,7.7812323570251465,-0.5329950211469685,1744060576.0370421,7.7812323570251465,-1.630700955924497,1744060576.0370443,7.7812323570251465,0.0,1744060576.0370462,7.7812323570251465,56568542496.923805,1744060576.0370474,7.7812323570251465,0.0,1744060576.0370486,7.7812323570251465,2.8826992599249125e-11,1744060576.0370495,7.7812323570251465,1.630700955924497,1744060576.0370507,7.7812323570251465,2.3482093763209815e-21,1744060576.0370517,7.7812323570251465,10,1744060576.0370526,7.7812323570251465,0.0,1744060576.0370536,7.7812323570251465,-22627416989.969524,1744060576.0370548,7.7812323570251465,0.0,1744060576.0370557,7.7812323570251465,28284271247.461903
+1744060576.0573077,7.801248073577881,-0.5329950211469685,1744060576.0573094,7.801248073577881,-1.630700955924497,1744060576.0573115,7.801248073577881,0.0,1744060576.0573134,7.801248073577881,56568542496.923805,1744060576.0573146,7.801248073577881,0.0,1744060576.0573308,7.801248073577881,2.8826992599249125e-11,1744060576.0573323,7.801248073577881,1.630700955924497,1744060576.0573332,7.801248073577881,2.3482093763209815e-21,1744060576.0573342,7.801248073577881,10,1744060576.0573351,7.801248073577881,0.0,1744060576.057336,7.801248073577881,-22627416989.969524,1744060576.057337,7.801248073577881,0.0,1744060576.0573378,7.801248073577881,28284271247.461903
+1744060576.077054,7.821226596832275,-0.5329950211469685,1744060576.0770557,7.821226596832275,-1.630700955924497,1744060576.0770578,7.821226596832275,0.0,1744060576.07706,7.821226596832275,56568542496.923805,1744060576.0770612,7.821226596832275,0.0,1744060576.0770624,7.821226596832275,2.8826992599249125e-11,1744060576.0770638,7.821226596832275,1.630700955924497,1744060576.0770648,7.821226596832275,2.3482093763209815e-21,1744060576.0770657,7.821226596832275,10,1744060576.0770667,7.821226596832275,0.0,1744060576.0770679,7.821226596832275,-22627416989.969524,1744060576.077069,7.821226596832275,0.0,1744060576.0770698,7.821226596832275,28284271247.461903
+1744060576.0971975,7.841235160827637,-0.5329950211469685,1744060576.0971997,7.841235160827637,-1.630700955924497,1744060576.0972018,7.841235160827637,0.0,1744060576.097204,7.841235160827637,56568542496.923805,1744060576.097205,7.841235160827637,0.0,1744060576.0972064,7.841235160827637,2.8826992599249125e-11,1744060576.0972075,7.841235160827637,1.630700955924497,1744060576.0972087,7.841235160827637,2.3482093763209815e-21,1744060576.09721,7.841235160827637,10,1744060576.097211,7.841235160827637,0.0,1744060576.0972118,7.841235160827637,-22627416989.969524,1744060576.0972133,7.841235160827637,0.0,1744060576.097214,7.841235160827637,28284271247.461903
+1744060576.1169672,7.861252307891846,-0.5329950211469685,1744060576.1169686,7.861252307891846,-1.630700955924497,1744060576.116971,7.861252307891846,0.0,1744060576.1169732,7.861252307891846,56568542496.923805,1744060576.116974,7.861252307891846,0.0,1744060576.1169753,7.861252307891846,2.8826992599249125e-11,1744060576.1169767,7.861252307891846,1.630700955924497,1744060576.1169777,7.861252307891846,2.3482093763209815e-21,1744060576.116979,7.861252307891846,10,1744060576.1169796,7.861252307891846,0.0,1744060576.1169808,7.861252307891846,-22627416989.969524,1744060576.1169822,7.861252307891846,0.0,1744060576.116983,7.861252307891846,28284271247.461903
+1744060576.1371071,7.881283760070801,-0.5329950211469685,1744060576.137109,7.881283760070801,-1.630700955924497,1744060576.1371112,7.881283760070801,0.0,1744060576.1371133,7.881283760070801,56568542496.923805,1744060576.1371143,7.881283760070801,0.0,1744060576.1371157,7.881283760070801,2.8826992599249125e-11,1744060576.137117,7.881283760070801,1.630700955924497,1744060576.137118,7.881283760070801,2.3482093763209815e-21,1744060576.1371195,7.881283760070801,10,1744060576.1371207,7.881283760070801,0.0,1744060576.1371217,7.881283760070801,-22627416989.969524,1744060576.1371229,7.881283760070801,0.0,1744060576.1371238,7.881283760070801,28284271247.461903
+1744060576.158129,7.901253938674927,-0.5329950211469685,1744060576.1581311,7.901253938674927,-1.630700955924497,1744060576.1581335,7.901253938674927,0.0,1744060576.158136,7.901253938674927,56568542496.923805,1744060576.1581368,7.901253938674927,0.0,1744060576.1581383,7.901253938674927,2.8826992599249125e-11,1744060576.15814,7.901253938674927,1.630700955924497,1744060576.158141,7.901253938674927,2.3482093763209815e-21,1744060576.1581426,7.901253938674927,10,1744060576.1581435,7.901253938674927,0.0,1744060576.1581447,7.901253938674927,-22627416989.969524,1744060576.1581461,7.901253938674927,0.0,1744060576.158147,7.901253938674927,28284271247.461903
+1744060576.1770186,7.921236753463745,-0.5329950211469685,1744060576.1770203,7.921236753463745,-1.630700955924497,1744060576.1770225,7.921236753463745,0.0,1744060576.1770246,7.921236753463745,56568542496.923805,1744060576.1770256,7.921236753463745,0.0,1744060576.177027,7.921236753463745,2.8826992599249125e-11,1744060576.1770282,7.921236753463745,1.630700955924497,1744060576.1770291,7.921236753463745,2.3482093763209815e-21,1744060576.1770303,7.921236753463745,10,1744060576.1770315,7.921236753463745,0.0,1744060576.1770322,7.921236753463745,-22627416989.969524,1744060576.1770487,7.921236753463745,0.0,1744060576.1770496,7.921236753463745,28284271247.461903
+1744060576.1976879,7.941465854644775,-0.5329950211469685,1744060576.1976905,7.941465854644775,-1.630700955924497,1744060576.1976936,7.941465854644775,0.0,1744060576.1976962,7.941465854644775,56568542496.923805,1744060576.1976984,7.941465854644775,0.0,1744060576.1977177,7.941465854644775,2.8826992599249125e-11,1744060576.197719,7.941465854644775,1.630700955924497,1744060576.1977203,7.941465854644775,2.3482093763209815e-21,1744060576.197722,7.941465854644775,10,1744060576.197723,7.941465854644775,0.0,1744060576.1977239,7.941465854644775,-22627416989.969524,1744060576.1977253,7.941465854644775,0.0,1744060576.1977262,7.941465854644775,28284271247.461903
+1744060576.2170138,7.961292266845703,-0.5329950211469685,1744060576.2170155,7.961292266845703,-1.630700955924497,1744060576.217018,7.961292266845703,0.0,1744060576.2170198,7.961292266845703,56568542496.923805,1744060576.217021,7.961292266845703,0.0,1744060576.217022,7.961292266845703,2.8826992599249125e-11,1744060576.2170231,7.961292266845703,1.630700955924497,1744060576.2170243,7.961292266845703,2.3482093763209815e-21,1744060576.2170255,7.961292266845703,10,1744060576.2170262,7.961292266845703,0.0,1744060576.2170274,7.961292266845703,-22627416989.969524,1744060576.2170284,7.961292266845703,0.0,1744060576.2170293,7.961292266845703,28284271247.461903
+1744060576.2370355,7.981272220611572,-0.5329950211469685,1744060576.2370374,7.981272220611572,-1.630700955924497,1744060576.2370396,7.981272220611572,0.0,1744060576.2370417,7.981272220611572,56568542496.923805,1744060576.2370427,7.981272220611572,0.0,1744060576.2370439,7.981272220611572,2.8826992599249125e-11,1744060576.237045,7.981272220611572,1.630700955924497,1744060576.2370462,7.981272220611572,2.3482093763209815e-21,1744060576.2370472,7.981272220611572,10,1744060576.2370484,7.981272220611572,0.0,1744060576.237049,7.981272220611572,-22627416989.969524,1744060576.2370503,7.981272220611572,0.0,1744060576.2370515,7.981272220611572,28284271247.461903
+1744060576.2582169,8.00127363204956,-0.9650938524113798,1744060576.2582188,8.00127363204956,-3.299825531517687,1744060576.2582211,8.00127363204956,0.0,1744060576.2582233,8.00127363204956,56568542496.923805,1744060576.2582245,8.00127363204956,0.0,1744060576.258226,8.00127363204956,5.833322524865891e-11,1744060576.258227,8.00127363204956,3.2998255315176874,1744060576.2582285,8.00127363204956,4.7517487648873344e-21,1744060576.2582302,8.00127363204956,10,1744060576.2582314,8.00127363204956,0.0,1744060576.2582324,8.00127363204956,-22627416989.969524,1744060576.2582335,8.00127363204956,0.0,1744060576.2582347,8.00127363204956,28284271247.461903
+1744060576.2768862,8.02122712135315,-0.9650938524113798,1744060576.2768881,8.02122712135315,-3.299825531517687,1744060576.27689,8.02122712135315,0.0,1744060576.2768922,8.02122712135315,56568542496.923805,1744060576.2768931,8.02122712135315,0.0,1744060576.2768946,8.02122712135315,5.833322524865891e-11,1744060576.2768958,8.02122712135315,3.2998255315176874,1744060576.2768967,8.02122712135315,4.7517487648873344e-21,1744060576.276898,8.02122712135315,10,1744060576.2768989,8.02122712135315,0.0,1744060576.2768998,8.02122712135315,-22627416989.969524,1744060576.276901,8.02122712135315,0.0,1744060576.2769022,8.02122712135315,28284271247.461903
+1744060576.2972155,8.04127287864685,-0.9650938524113798,1744060576.2972174,8.04127287864685,-3.299825531517687,1744060576.2972195,8.04127287864685,0.0,1744060576.2972217,8.04127287864685,56568542496.923805,1744060576.2972226,8.04127287864685,0.0,1744060576.297224,8.04127287864685,5.833322524865891e-11,1744060576.297225,8.04127287864685,3.2998255315176874,1744060576.2972262,8.04127287864685,4.7517487648873344e-21,1744060576.2972274,8.04127287864685,10,1744060576.2972283,8.04127287864685,0.0,1744060576.297229,8.04127287864685,-22627416989.969524,1744060576.2972302,8.04127287864685,0.0,1744060576.2972312,8.04127287864685,28284271247.461903
+1744060576.3170154,8.06129240989685,-0.9650938524113798,1744060576.317017,8.06129240989685,-3.299825531517687,1744060576.3170192,8.06129240989685,0.0,1744060576.3170211,8.06129240989685,56568542496.923805,1744060576.3170223,8.06129240989685,0.0,1744060576.3170235,8.06129240989685,5.833322524865891e-11,1744060576.3170247,8.06129240989685,3.2998255315176874,1744060576.317026,8.06129240989685,4.7517487648873344e-21,1744060576.3170269,8.06129240989685,10,1744060576.3170278,8.06129240989685,0.0,1744060576.3170285,8.06129240989685,-22627416989.969524,1744060576.3170297,8.06129240989685,0.0,1744060576.3170307,8.06129240989685,28284271247.461903
+1744060576.3369403,8.081230878829956,-0.9650938524113798,1744060576.3369424,8.081230878829956,-3.299825531517687,1744060576.3369443,8.081230878829956,0.0,1744060576.3369465,8.081230878829956,56568542496.923805,1744060576.3369472,8.081230878829956,0.0,1744060576.3369484,8.081230878829956,5.833322524865891e-11,1744060576.3369498,8.081230878829956,3.2998255315176874,1744060576.3369508,8.081230878829956,4.7517487648873344e-21,1744060576.3369517,8.081230878829956,10,1744060576.336953,8.081230878829956,0.0,1744060576.3369539,8.081230878829956,-22627416989.969524,1744060576.3369548,8.081230878829956,0.0,1744060576.3369555,8.081230878829956,28284271247.461903
+1744060576.3577442,8.101243495941162,-0.9650938524113798,1744060576.3577461,8.101243495941162,-3.299825531517687,1744060576.357748,8.101243495941162,0.0,1744060576.3577502,8.101243495941162,56568542496.923805,1744060576.3577514,8.101243495941162,0.0,1744060576.3577526,8.101243495941162,5.833322524865891e-11,1744060576.3577538,8.101243495941162,3.2998255315176874,1744060576.357755,8.101243495941162,4.7517487648873344e-21,1744060576.3577561,8.101243495941162,10,1744060576.357757,8.101243495941162,0.0,1744060576.357758,8.101243495941162,-22627416989.969524,1744060576.3577845,8.101243495941162,0.0,1744060576.357786,8.101243495941162,28284271247.461903
+1744060576.3769562,8.121224164962769,-0.9650938524113798,1744060576.376958,8.121224164962769,-3.299825531517687,1744060576.37696,8.121224164962769,0.0,1744060576.376962,8.121224164962769,56568542496.923805,1744060576.3769634,8.121224164962769,0.0,1744060576.3769643,8.121224164962769,5.833322524865891e-11,1744060576.3769655,8.121224164962769,3.2998255315176874,1744060576.3769667,8.121224164962769,4.7517487648873344e-21,1744060576.376968,8.121224164962769,10,1744060576.3769686,8.121224164962769,0.0,1744060576.3769698,8.121224164962769,-22627416989.969524,1744060576.3769708,8.121224164962769,0.0,1744060576.3769715,8.121224164962769,28284271247.461903
+1744060576.3969643,8.141228437423706,-0.9650938524113798,1744060576.3969665,8.141228437423706,-3.299825531517687,1744060576.3969681,8.141228437423706,0.0,1744060576.3969703,8.141228437423706,56568542496.923805,1744060576.3969712,8.141228437423706,0.0,1744060576.3969727,8.141228437423706,5.833322524865891e-11,1744060576.3969736,8.141228437423706,3.2998255315176874,1744060576.3969746,8.141228437423706,4.7517487648873344e-21,1744060576.3969758,8.141228437423706,10,1744060576.3969772,8.141228437423706,0.0,1744060576.396978,8.141228437423706,-22627416989.969524,1744060576.3969789,8.141228437423706,0.0,1744060576.39698,8.141228437423706,28284271247.461903
+1744060576.4169579,8.161231994628906,-0.9650938524113798,1744060576.4169598,8.161231994628906,-3.299825531517687,1744060576.416962,8.161231994628906,0.0,1744060576.4169638,8.161231994628906,56568542496.923805,1744060576.4169645,8.161231994628906,0.0,1744060576.416966,8.161231994628906,5.833322524865891e-11,1744060576.4169672,8.161231994628906,3.2998255315176874,1744060576.416968,8.161231994628906,4.7517487648873344e-21,1744060576.4169693,8.161231994628906,10,1744060576.4169703,8.161231994628906,0.0,1744060576.416971,8.161231994628906,-22627416989.969524,1744060576.416972,8.161231994628906,0.0,1744060576.416973,8.161231994628906,28284271247.461903
+1744060576.436925,8.181225299835205,-0.9650938524113798,1744060576.4369278,8.181225299835205,-3.299825531517687,1744060576.4369307,8.181225299835205,0.0,1744060576.436934,8.181225299835205,56568542496.923805,1744060576.4369354,8.181225299835205,0.0,1744060576.4369373,8.181225299835205,5.833322524865891e-11,1744060576.4369385,8.181225299835205,3.2998255315176874,1744060576.4369395,8.181225299835205,4.7517487648873344e-21,1744060576.4369404,8.181225299835205,10,1744060576.4369416,8.181225299835205,0.0,1744060576.4369423,8.181225299835205,-22627416989.969524,1744060576.4369438,8.181225299835205,0.0,1744060576.436945,8.181225299835205,28284271247.461903
+1744060576.4578755,8.20126748085022,-0.9650938524113798,1744060576.4578784,8.20126748085022,-3.299825531517687,1744060576.4578822,8.20126748085022,0.0,1744060576.457886,8.20126748085022,56568542496.923805,1744060576.457888,8.20126748085022,0.0,1744060576.4578903,8.20126748085022,5.833322524865891e-11,1744060576.4578927,8.20126748085022,3.2998255315176874,1744060576.4579005,8.20126748085022,4.7517487648873344e-21,1744060576.4579024,8.20126748085022,10,1744060576.4579046,8.20126748085022,0.0,1744060576.457914,8.20126748085022,-22627416989.969524,1744060576.4579172,8.20126748085022,0.0,1744060576.4579196,8.20126748085022,28284271247.461903
+1744060576.4769926,8.22123908996582,-0.9650938524113798,1744060576.4769945,8.22123908996582,-3.299825531517687,1744060576.4769967,8.22123908996582,0.0,1744060576.4769988,8.22123908996582,56568542496.923805,1744060576.477,8.22123908996582,0.0,1744060576.4770012,8.22123908996582,5.833322524865891e-11,1744060576.4770024,8.22123908996582,3.2998255315176874,1744060576.4770036,8.22123908996582,4.7517487648873344e-21,1744060576.4770045,8.22123908996582,10,1744060576.4770057,8.22123908996582,0.0,1744060576.4770067,8.22123908996582,-22627416989.969524,1744060576.4770076,8.22123908996582,0.0,1744060576.4770086,8.22123908996582,28284271247.461903
+1744060576.496994,8.241249561309814,-0.9650938524113798,1744060576.496996,8.241249561309814,-3.299825531517687,1744060576.4969985,8.241249561309814,0.0,1744060576.4970007,8.241249561309814,56568542496.923805,1744060576.4970016,8.241249561309814,0.0,1744060576.4970028,8.241249561309814,5.833322524865891e-11,1744060576.497004,8.241249561309814,3.2998255315176874,1744060576.497005,8.241249561309814,4.7517487648873344e-21,1744060576.4970067,8.241249561309814,10,1744060576.4970074,8.241249561309814,0.0,1744060576.4970083,8.241249561309814,-22627416989.969524,1744060576.497009,8.241249561309814,0.0,1744060576.4970102,8.241249561309814,28284271247.461903
+1744060576.516927,8.261231184005737,-0.9650938524113798,1744060576.5169287,8.261231184005737,-3.299825531517687,1744060576.5169308,8.261231184005737,0.0,1744060576.516933,8.261231184005737,56568542496.923805,1744060576.516934,8.261231184005737,0.0,1744060576.516935,8.261231184005737,5.833322524865891e-11,1744060576.5169365,8.261231184005737,3.2998255315176874,1744060576.5169377,8.261231184005737,4.7517487648873344e-21,1744060576.5169387,8.261231184005737,10,1744060576.5169399,8.261231184005737,0.0,1744060576.5169406,8.261231184005737,-22627416989.969524,1744060576.5169415,8.261231184005737,0.0,1744060576.5169425,8.261231184005737,28284271247.461903
+1744060576.5369556,8.281252145767212,-0.9650938524113798,1744060576.5369577,8.281252145767212,-3.299825531517687,1744060576.5369604,8.281252145767212,0.0,1744060576.5369623,8.281252145767212,56568542496.923805,1744060576.5369632,8.281252145767212,0.0,1744060576.5369647,8.281252145767212,5.833322524865891e-11,1744060576.5369656,8.281252145767212,3.2998255315176874,1744060576.5369668,8.281252145767212,4.7517487648873344e-21,1744060576.5369682,8.281252145767212,10,1744060576.536969,8.281252145767212,0.0,1744060576.53697,8.281252145767212,-22627416989.969524,1744060576.536971,8.281252145767212,0.0,1744060576.536972,8.281252145767212,28284271247.461903
+1744060576.5582848,8.301278829574585,-0.9650938524113798,1744060576.558287,8.301278829574585,-3.299825531517687,1744060576.558289,8.301278829574585,0.0,1744060576.5582914,8.301278829574585,56568542496.923805,1744060576.5582924,8.301278829574585,0.0,1744060576.558294,8.301278829574585,5.833322524865891e-11,1744060576.5582952,8.301278829574585,3.2998255315176874,1744060576.5582967,8.301278829574585,4.7517487648873344e-21,1744060576.5582979,8.301278829574585,10,1744060576.558299,8.301278829574585,0.0,1744060576.5583005,8.301278829574585,-22627416989.969524,1744060576.5583014,8.301278829574585,0.0,1744060576.5583026,8.301278829574585,28284271247.461903
+1744060576.5769749,8.321264505386353,-0.9650938524113798,1744060576.5769765,8.321264505386353,-3.299825531517687,1744060576.576979,8.321264505386353,0.0,1744060576.576981,8.321264505386353,56568542496.923805,1744060576.576982,8.321264505386353,0.0,1744060576.5769832,8.321264505386353,5.833322524865891e-11,1744060576.5769846,8.321264505386353,3.2998255315176874,1744060576.5769856,8.321264505386353,4.7517487648873344e-21,1744060576.5769866,8.321264505386353,10,1744060576.5769877,8.321264505386353,0.0,1744060576.5769887,8.321264505386353,-22627416989.969524,1744060576.5769894,8.321264505386353,0.0,1744060576.5769904,8.321264505386353,28284271247.461903
+1744060576.5969865,8.341238260269165,-0.9650938524113798,1744060576.5969887,8.341238260269165,-3.299825531517687,1744060576.5969908,8.341238260269165,0.0,1744060576.596993,8.341238260269165,56568542496.923805,1744060576.5969944,8.341238260269165,0.0,1744060576.5969954,8.341238260269165,5.833322524865891e-11,1744060576.5969965,8.341238260269165,3.2998255315176874,1744060576.5969977,8.341238260269165,4.7517487648873344e-21,1744060576.596999,8.341238260269165,10,1744060576.597,8.341238260269165,0.0,1744060576.597001,8.341238260269165,-22627416989.969524,1744060576.597002,8.341238260269165,0.0,1744060576.597003,8.341238260269165,28284271247.461903
+1744060576.616971,8.361271381378174,-0.9650938524113798,1744060576.6169727,8.361271381378174,-3.299825531517687,1744060576.616975,8.361271381378174,0.0,1744060576.616977,8.361271381378174,56568542496.923805,1744060576.616978,8.361271381378174,0.0,1744060576.6169791,8.361271381378174,5.833322524865891e-11,1744060576.6169803,8.361271381378174,3.2998255315176874,1744060576.6169815,8.361271381378174,4.7517487648873344e-21,1744060576.6169825,8.361271381378174,10,1744060576.6169837,8.361271381378174,0.0,1744060576.6169846,8.361271381378174,-22627416989.969524,1744060576.6169853,8.361271381378174,0.0,1744060576.6169863,8.361271381378174,28284271247.461903
+1744060576.6370704,8.381275653839111,-0.9650938524113798,1744060576.6370723,8.381275653839111,-3.299825531517687,1744060576.6370747,8.381275653839111,0.0,1744060576.6370769,8.381275653839111,56568542496.923805,1744060576.6370778,8.381275653839111,0.0,1744060576.637079,8.381275653839111,5.833322524865891e-11,1744060576.6370804,8.381275653839111,3.2998255315176874,1744060576.6370814,8.381275653839111,4.7517487648873344e-21,1744060576.6370823,8.381275653839111,10,1744060576.6370833,8.381275653839111,0.0,1744060576.6370842,8.381275653839111,-22627416989.969524,1744060576.6370852,8.381275653839111,0.0,1744060576.6370862,8.381275653839111,28284271247.461903
+1744060576.6583347,8.40129542350769,-0.9650938524113798,1744060576.658338,8.40129542350769,-3.299825531517687,1744060576.658342,8.40129542350769,0.0,1744060576.6583457,8.40129542350769,56568542496.923805,1744060576.6583478,8.40129542350769,0.0,1744060576.6583493,8.40129542350769,5.833322524865891e-11,1744060576.6583507,8.40129542350769,3.2998255315176874,1744060576.6583705,8.40129542350769,4.7517487648873344e-21,1744060576.6583722,8.40129542350769,10,1744060576.658373,8.40129542350769,0.0,1744060576.6583743,8.40129542350769,-22627416989.969524,1744060576.6583755,8.40129542350769,0.0,1744060576.6583765,8.40129542350769,28284271247.461903
+1744060576.676998,8.421233654022217,-0.9650938524113798,1744060576.6769996,8.421233654022217,-3.299825531517687,1744060576.677002,8.421233654022217,0.0,1744060576.677004,8.421233654022217,56568542496.923805,1744060576.677005,8.421233654022217,0.0,1744060576.6770062,8.421233654022217,5.833322524865891e-11,1744060576.6770077,8.421233654022217,3.2998255315176874,1744060576.6770086,8.421233654022217,4.7517487648873344e-21,1744060576.6770096,8.421233654022217,10,1744060576.677011,8.421233654022217,0.0,1744060576.677012,8.421233654022217,-22627416989.969524,1744060576.677019,8.421233654022217,0.0,1744060576.6770198,8.421233654022217,28284271247.461903
+1744060576.6970918,8.441227436065674,-0.9650938524113798,1744060576.697113,8.441227436065674,-3.299825531517687,1744060576.6971161,8.441227436065674,0.0,1744060576.6971188,8.441227436065674,56568542496.923805,1744060576.6971202,8.441227436065674,0.0,1744060576.6971216,8.441227436065674,5.833322524865891e-11,1744060576.6971228,8.441227436065674,3.2998255315176874,1744060576.697124,8.441227436065674,4.7517487648873344e-21,1744060576.6971257,8.441227436065674,10,1744060576.6971266,8.441227436065674,0.0,1744060576.6971276,8.441227436065674,-22627416989.969524,1744060576.697129,8.441227436065674,0.0,1744060576.69713,8.441227436065674,28284271247.461903
+1744060576.71698,8.461234092712402,-0.9650938524113798,1744060576.7169816,8.461234092712402,-3.299825531517687,1744060576.716984,8.461234092712402,0.0,1744060576.7169862,8.461234092712402,56568542496.923805,1744060576.7169871,8.461234092712402,0.0,1744060576.7169883,8.461234092712402,5.833322524865891e-11,1744060576.7169898,8.461234092712402,3.2998255315176874,1744060576.7169907,8.461234092712402,4.7517487648873344e-21,1744060576.7169917,8.461234092712402,10,1744060576.7169929,8.461234092712402,0.0,1744060576.7169938,8.461234092712402,-22627416989.969524,1744060576.7169945,8.461234092712402,0.0,1744060576.7169955,8.461234092712402,28284271247.461903
+1744060576.7371972,8.481256008148193,-0.9650938524113798,1744060576.7372196,8.481256008148193,-3.299825531517687,1744060576.737222,8.481256008148193,0.0,1744060576.737224,8.481256008148193,56568542496.923805,1744060576.7372253,8.481256008148193,0.0,1744060576.7372265,8.481256008148193,5.833322524865891e-11,1744060576.7372468,8.481256008148193,3.2998255315176874,1744060576.7372477,8.481256008148193,4.7517487648873344e-21,1744060576.7372491,8.481256008148193,10,1744060576.7372499,8.481256008148193,0.0,1744060576.7372508,8.481256008148193,-22627416989.969524,1744060576.7372518,8.481256008148193,0.0,1744060576.737253,8.481256008148193,28284271247.461903
+1744060576.7573862,8.501259803771973,-1.5410234300420387,1744060576.757388,8.501259803771973,-5.526086326831212,1744060576.75739,8.501259803771973,0.0,1744060576.7573922,8.501259803771973,56568542496.923805,1744060576.7573931,8.501259803771973,0.0,1744060576.7573943,8.501259803771973,9.768832787200024e-11,1744060576.7573955,8.501259803771973,5.526086326831212,1744060576.7573965,8.501259803771973,7.957564309640703e-21,1744060576.7573974,8.501259803771973,10,1744060576.7573988,8.501259803771973,0.0,1744060576.7573996,8.501259803771973,-22627416989.969524,1744060576.7574008,8.501259803771973,0.0,1744060576.757402,8.501259803771973,28284271247.461903
+1744060576.7770839,8.5212562084198,-1.5410234300420387,1744060576.7770865,8.5212562084198,-5.526086326831212,1744060576.7770896,8.5212562084198,0.0,1744060576.777093,8.5212562084198,56568542496.923805,1744060576.7770944,8.5212562084198,0.0,1744060576.7770987,8.5212562084198,9.768832787200024e-11,1744060576.7771006,8.5212562084198,5.526086326831212,1744060576.777102,8.5212562084198,7.957564309640703e-21,1744060576.7771041,8.5212562084198,10,1744060576.7771058,8.5212562084198,0.0,1744060576.7771075,8.5212562084198,-22627416989.969524,1744060576.777109,8.5212562084198,0.0,1744060576.77711,8.5212562084198,28284271247.461903
+1744060576.7973375,8.541293859481812,-1.5410234300420387,1744060576.7973394,8.541293859481812,-5.526086326831212,1744060576.7973413,8.541293859481812,0.0,1744060576.797344,8.541293859481812,56568542496.923805,1744060576.797345,8.541293859481812,0.0,1744060576.7973464,8.541293859481812,9.768832787200024e-11,1744060576.7973475,8.541293859481812,5.526086326831212,1744060576.7973485,8.541293859481812,7.957564309640703e-21,1744060576.7973497,8.541293859481812,10,1744060576.7973506,8.541293859481812,0.0,1744060576.7973516,8.541293859481812,-22627416989.969524,1744060576.7973528,8.541293859481812,0.0,1744060576.7973537,8.541293859481812,28284271247.461903
+1744060576.816936,8.561229705810547,-1.5410234300420387,1744060576.8169377,8.561229705810547,-5.526086326831212,1744060576.8169398,8.561229705810547,0.0,1744060576.816942,8.561229705810547,56568542496.923805,1744060576.8169432,8.561229705810547,0.0,1744060576.8169444,8.561229705810547,9.768832787200024e-11,1744060576.8169456,8.561229705810547,5.526086326831212,1744060576.816947,8.561229705810547,7.957564309640703e-21,1744060576.816948,8.561229705810547,10,1744060576.8169487,8.561229705810547,0.0,1744060576.8169498,8.561229705810547,-22627416989.969524,1744060576.8169508,8.561229705810547,0.0,1744060576.8169515,8.561229705810547,28284271247.461903
+1744060576.8370066,8.581233263015747,-1.5410234300420387,1744060576.8370092,8.581233263015747,-5.526086326831212,1744060576.8370123,8.581233263015747,0.0,1744060576.8370152,8.581233263015747,56568542496.923805,1744060576.8370166,8.581233263015747,0.0,1744060576.8370187,8.581233263015747,9.768832787200024e-11,1744060576.8370202,8.581233263015747,5.526086326831212,1744060576.837022,8.581233263015747,7.957564309640703e-21,1744060576.8370237,8.581233263015747,10,1744060576.8370252,8.581233263015747,0.0,1744060576.8370266,8.581233263015747,-22627416989.969524,1744060576.8370278,8.581233263015747,0.0,1744060576.8370292,8.581233263015747,28284271247.461903
+1744060576.8575618,8.601337194442749,-1.5410234300420387,1744060576.8575635,8.601337194442749,-5.526086326831212,1744060576.8575654,8.601337194442749,0.0,1744060576.8575675,8.601337194442749,56568542496.923805,1744060576.8575687,8.601337194442749,0.0,1744060576.8575697,8.601337194442749,9.768832787200024e-11,1744060576.857571,8.601337194442749,5.526086326831212,1744060576.857572,8.601337194442749,7.957564309640703e-21,1744060576.857573,8.601337194442749,10,1744060576.8575742,8.601337194442749,0.0,1744060576.8575752,8.601337194442749,-22627416989.969524,1744060576.857576,8.601337194442749,0.0,1744060576.8575768,8.601337194442749,28284271247.461903
+1744060576.876981,8.62125539779663,-1.5410234300420387,1744060576.876983,8.62125539779663,-5.526086326831212,1744060576.8769848,8.62125539779663,0.0,1744060576.8769872,8.62125539779663,56568542496.923805,1744060576.8769882,8.62125539779663,0.0,1744060576.8769891,8.62125539779663,9.768832787200024e-11,1744060576.8769906,8.62125539779663,5.526086326831212,1744060576.8769915,8.62125539779663,7.957564309640703e-21,1744060576.8769927,8.62125539779663,10,1744060576.876994,8.62125539779663,0.0,1744060576.8769948,8.62125539779663,-22627416989.969524,1744060576.8769958,8.62125539779663,0.0,1744060576.8769968,8.62125539779663,28284271247.461903
+1744060576.8978639,8.641267538070679,-1.5410234300420387,1744060576.8978677,8.641267538070679,-5.526086326831212,1744060576.897872,8.641267538070679,0.0,1744060576.8978755,8.641267538070679,56568542496.923805,1744060576.897877,8.641267538070679,0.0,1744060576.8978796,8.641267538070679,9.768832787200024e-11,1744060576.8978817,8.641267538070679,5.526086326831212,1744060576.8978837,8.641267538070679,7.957564309640703e-21,1744060576.8978858,8.641267538070679,10,1744060576.897887,8.641267538070679,0.0,1744060576.897888,8.641267538070679,-22627416989.969524,1744060576.8978894,8.641267538070679,0.0,1744060576.8978903,8.641267538070679,28284271247.461903
+1744060576.916951,8.661264896392822,-1.5410234300420387,1744060576.9169526,8.661264896392822,-5.526086326831212,1744060576.916955,8.661264896392822,0.0,1744060576.916957,8.661264896392822,56568542496.923805,1744060576.9169579,8.661264896392822,0.0,1744060576.9169595,8.661264896392822,9.768832787200024e-11,1744060576.9169607,8.661264896392822,5.526086326831212,1744060576.916962,8.661264896392822,7.957564309640703e-21,1744060576.9169629,8.661264896392822,10,1744060576.9169638,8.661264896392822,0.0,1744060576.9169648,8.661264896392822,-22627416989.969524,1744060576.916966,8.661264896392822,0.0,1744060576.916967,8.661264896392822,28284271247.461903
+1744060576.9370763,8.681265115737915,-1.5410234300420387,1744060576.937078,8.681265115737915,-5.526086326831212,1744060576.9370804,8.681265115737915,0.0,1744060576.9370823,8.681265115737915,56568542496.923805,1744060576.9370835,8.681265115737915,0.0,1744060576.9370847,8.681265115737915,9.768832787200024e-11,1744060576.9370859,8.681265115737915,5.526086326831212,1744060576.9370873,8.681265115737915,7.957564309640703e-21,1744060576.9370883,8.681265115737915,10,1744060576.9370892,8.681265115737915,0.0,1744060576.9370902,8.681265115737915,-22627416989.969524,1744060576.937091,8.681265115737915,0.0,1744060576.937092,8.681265115737915,28284271247.461903
+1744060576.9576712,8.701258182525635,-1.5410234300420387,1744060576.9576726,8.701258182525635,-5.526086326831212,1744060576.9576747,8.701258182525635,0.0,1744060576.9576771,8.701258182525635,56568542496.923805,1744060576.957678,8.701258182525635,0.0,1744060576.9576793,8.701258182525635,9.768832787200024e-11,1744060576.9576805,8.701258182525635,5.526086326831212,1744060576.9576817,8.701258182525635,7.957564309640703e-21,1744060576.9576826,8.701258182525635,10,1744060576.9576838,8.701258182525635,0.0,1744060576.9576848,8.701258182525635,-22627416989.969524,1744060576.9576857,8.701258182525635,0.0,1744060576.957687,8.701258182525635,28284271247.461903
+1744060576.9769626,8.72126293182373,-1.5410234300420387,1744060576.9769647,8.72126293182373,-5.526086326831212,1744060576.9769666,8.72126293182373,0.0,1744060576.9769688,8.72126293182373,56568542496.923805,1744060576.9769697,8.72126293182373,0.0,1744060576.9769707,8.72126293182373,9.768832787200024e-11,1744060576.976972,8.72126293182373,5.526086326831212,1744060576.976973,8.72126293182373,7.957564309640703e-21,1744060576.976974,8.72126293182373,10,1744060576.9769752,8.72126293182373,0.0,1744060576.9769762,8.72126293182373,-22627416989.969524,1744060576.976977,8.72126293182373,0.0,1744060576.976978,8.72126293182373,28284271247.461903
+1744060576.9970927,8.741272211074829,-1.5410234300420387,1744060576.9970956,8.741272211074829,-5.526086326831212,1744060576.9970992,8.741272211074829,0.0,1744060576.9971025,8.741272211074829,56568542496.923805,1744060576.9971042,8.741272211074829,0.0,1744060576.9971068,8.741272211074829,9.768832787200024e-11,1744060576.9971085,8.741272211074829,5.526086326831212,1744060576.9971097,8.741272211074829,7.957564309640703e-21,1744060576.9971385,8.741272211074829,10,1744060576.9971397,8.741272211074829,0.0,1744060576.9971404,8.741272211074829,-22627416989.969524,1744060576.9971416,8.741272211074829,0.0,1744060576.9971426,8.741272211074829,28284271247.461903
+1744060577.0169156,8.761224031448364,-1.5410234300420387,1744060577.0169172,8.761224031448364,-5.526086326831212,1744060577.0169196,8.761224031448364,0.0,1744060577.0169215,8.761224031448364,56568542496.923805,1744060577.0169227,8.761224031448364,0.0,1744060577.016924,8.761224031448364,9.768832787200024e-11,1744060577.0169249,8.761224031448364,5.526086326831212,1744060577.0169263,8.761224031448364,7.957564309640703e-21,1744060577.0169272,8.761224031448364,10,1744060577.0169282,8.761224031448364,0.0,1744060577.0169294,8.761224031448364,-22627416989.969524,1744060577.0169303,8.761224031448364,0.0,1744060577.016931,8.761224031448364,28284271247.461903
+1744060577.0370085,8.781296014785767,-1.5410234300420387,1744060577.0370104,8.781296014785767,-5.526086326831212,1744060577.0370126,8.781296014785767,0.0,1744060577.0370145,8.781296014785767,56568542496.923805,1744060577.0370154,8.781296014785767,0.0,1744060577.0370169,8.781296014785767,9.768832787200024e-11,1744060577.0370178,8.781296014785767,5.526086326831212,1744060577.0370193,8.781296014785767,7.957564309640703e-21,1744060577.0370202,8.781296014785767,10,1744060577.037021,8.781296014785767,0.0,1744060577.0370219,8.781296014785767,-22627416989.969524,1744060577.037023,8.781296014785767,0.0,1744060577.037024,8.781296014785767,28284271247.461903
+1744060577.0574481,8.801268339157104,-1.5410234300420387,1744060577.05745,8.801268339157104,-5.526086326831212,1744060577.0574522,8.801268339157104,0.0,1744060577.0574543,8.801268339157104,56568542496.923805,1744060577.0574553,8.801268339157104,0.0,1744060577.0574567,8.801268339157104,9.768832787200024e-11,1744060577.0574577,8.801268339157104,5.526086326831212,1744060577.0574586,8.801268339157104,7.957564309640703e-21,1744060577.05746,8.801268339157104,10,1744060577.057461,8.801268339157104,0.0,1744060577.057462,8.801268339157104,-22627416989.969524,1744060577.057463,8.801268339157104,0.0,1744060577.057464,8.801268339157104,28284271247.461903
+1744060577.0769196,8.821228265762329,-1.5410234300420387,1744060577.0769215,8.821228265762329,-5.526086326831212,1744060577.0769236,8.821228265762329,0.0,1744060577.0769258,8.821228265762329,56568542496.923805,1744060577.0769265,8.821228265762329,0.0,1744060577.0769277,8.821228265762329,9.768832787200024e-11,1744060577.076929,8.821228265762329,5.526086326831212,1744060577.07693,8.821228265762329,7.957564309640703e-21,1744060577.076931,8.821228265762329,10,1744060577.0769322,8.821228265762329,0.0,1744060577.0769331,8.821228265762329,-22627416989.969524,1744060577.076934,8.821228265762329,0.0,1744060577.076935,8.821228265762329,28284271247.461903
+1744060577.0969505,8.841247797012329,-1.5410234300420387,1744060577.0969524,8.841247797012329,-5.526086326831212,1744060577.0969546,8.841247797012329,0.0,1744060577.0969567,8.841247797012329,56568542496.923805,1744060577.0969577,8.841247797012329,0.0,1744060577.0969586,8.841247797012329,9.768832787200024e-11,1744060577.09696,8.841247797012329,5.526086326831212,1744060577.096961,8.841247797012329,7.957564309640703e-21,1744060577.096962,8.841247797012329,10,1744060577.0969632,8.841247797012329,0.0,1744060577.0969641,8.841247797012329,-22627416989.969524,1744060577.096965,8.841247797012329,0.0,1744060577.0969658,8.841247797012329,28284271247.461903
+1744060577.117423,8.861321926116943,-1.5410234300420387,1744060577.1174254,8.861321926116943,-5.526086326831212,1744060577.1174278,8.861321926116943,0.0,1744060577.11743,8.861321926116943,56568542496.923805,1744060577.117431,8.861321926116943,0.0,1744060577.1174324,8.861321926116943,9.768832787200024e-11,1744060577.1174338,8.861321926116943,5.526086326831212,1744060577.1174355,8.861321926116943,7.957564309640703e-21,1744060577.1174366,8.861321926116943,10,1744060577.1174374,8.861321926116943,0.0,1744060577.1174386,8.861321926116943,-22627416989.969524,1744060577.1174397,8.861321926116943,0.0,1744060577.1174405,8.861321926116943,28284271247.461903
+1744060577.1368887,8.881226301193237,-1.5410234300420387,1744060577.1368906,8.881226301193237,-5.526086326831212,1744060577.136893,8.881226301193237,0.0,1744060577.1368952,8.881226301193237,56568542496.923805,1744060577.1368964,8.881226301193237,0.0,1744060577.1368973,8.881226301193237,9.768832787200024e-11,1744060577.1368983,8.881226301193237,5.526086326831212,1744060577.1368992,8.881226301193237,7.957564309640703e-21,1744060577.136901,8.881226301193237,10,1744060577.1369016,8.881226301193237,0.0,1744060577.1369026,8.881226301193237,-22627416989.969524,1744060577.1369038,8.881226301193237,0.0,1744060577.1369047,8.881226301193237,28284271247.461903
+1744060577.1572785,8.901269674301147,-1.5410234300420387,1744060577.1572802,8.901269674301147,-5.526086326831212,1744060577.1572826,8.901269674301147,0.0,1744060577.1572845,8.901269674301147,56568542496.923805,1744060577.1572857,8.901269674301147,0.0,1744060577.1572866,8.901269674301147,9.768832787200024e-11,1744060577.1572878,8.901269674301147,5.526086326831212,1744060577.1572893,8.901269674301147,7.957564309640703e-21,1744060577.1572905,8.901269674301147,10,1744060577.157292,8.901269674301147,0.0,1744060577.1572928,8.901269674301147,-22627416989.969524,1744060577.1572938,8.901269674301147,0.0,1744060577.1572945,8.901269674301147,28284271247.461903
+1744060577.1769433,8.921256303787231,-1.5410234300420387,1744060577.176946,8.921256303787231,-5.526086326831212,1744060577.1769493,8.921256303787231,0.0,1744060577.1769526,8.921256303787231,56568542496.923805,1744060577.1769543,8.921256303787231,0.0,1744060577.1769564,8.921256303787231,9.768832787200024e-11,1744060577.1769583,8.921256303787231,5.526086326831212,1744060577.17696,8.921256303787231,7.957564309640703e-21,1744060577.176962,8.921256303787231,10,1744060577.1769633,8.921256303787231,0.0,1744060577.1769648,8.921256303787231,-22627416989.969524,1744060577.176966,8.921256303787231,0.0,1744060577.176967,8.921256303787231,28284271247.461903
+1744060577.1973379,8.941236019134521,-1.5410234300420387,1744060577.19734,8.941236019134521,-5.526086326831212,1744060577.1973436,8.941236019134521,0.0,1744060577.1973462,8.941236019134521,56568542496.923805,1744060577.1973479,8.941236019134521,0.0,1744060577.1973493,8.941236019134521,9.768832787200024e-11,1744060577.1973515,8.941236019134521,5.526086326831212,1744060577.1973531,8.941236019134521,7.957564309640703e-21,1744060577.1973548,8.941236019134521,10,1744060577.1973562,8.941236019134521,0.0,1744060577.197358,8.941236019134521,-22627416989.969524,1744060577.197359,8.941236019134521,0.0,1744060577.1973603,8.941236019134521,28284271247.461903
+1744060577.2170036,8.961261987686157,-1.5410234300420387,1744060577.2170053,8.961261987686157,-5.526086326831212,1744060577.2170074,8.961261987686157,0.0,1744060577.2170098,8.961261987686157,56568542496.923805,1744060577.2170107,8.961261987686157,0.0,1744060577.217012,8.961261987686157,9.768832787200024e-11,1744060577.2170382,8.961261987686157,5.526086326831212,1744060577.2170393,8.961261987686157,7.957564309640703e-21,1744060577.2170403,8.961261987686157,10,1744060577.2170415,8.961261987686157,0.0,1744060577.2170424,8.961261987686157,-22627416989.969524,1744060577.2170434,8.961261987686157,0.0,1744060577.2170446,8.961261987686157,28284271247.461903
+1744060577.236939,8.98125672340393,-1.5410234300420387,1744060577.2369409,8.98125672340393,-5.526086326831212,1744060577.236943,8.98125672340393,0.0,1744060577.236946,8.98125672340393,56568542496.923805,1744060577.236948,8.98125672340393,0.0,1744060577.23695,8.98125672340393,9.768832787200024e-11,1744060577.2369516,8.98125672340393,5.526086326831212,1744060577.2369533,8.98125672340393,7.957564309640703e-21,1744060577.236955,8.98125672340393,10,1744060577.2369564,8.98125672340393,0.0,1744060577.2369583,8.98125672340393,-22627416989.969524,1744060577.2369597,8.98125672340393,0.0,1744060577.2369611,8.98125672340393,28284271247.461903
+1744060577.2573068,9.001266241073608,-2.232603209381735,1744060577.2573087,9.001266241073608,-8.261683107326098,1744060577.2573109,9.001266241073608,0.0,1744060577.257313,9.001266241073608,56568542496.923805,1744060577.257314,9.001266241073608,0.0,1744060577.2573152,9.001266241073608,1.4604730371918813e-10,1744060577.2573164,9.001266241073608,8.261683107326098,1744060577.2573175,9.001266241073608,1.1896823672769279e-20,1744060577.2573187,9.001266241073608,10,1744060577.2573197,9.001266241073608,0.0,1744060577.2573204,9.001266241073608,-22627416989.969524,1744060577.2573218,9.001266241073608,0.0,1744060577.2573225,9.001266241073608,28284271247.461903
+1744060577.2769554,9.021254539489746,-2.232603209381735,1744060577.2769575,9.021254539489746,-8.261683107326098,1744060577.2769594,9.021254539489746,0.0,1744060577.2769616,9.021254539489746,56568542496.923805,1744060577.2769628,9.021254539489746,0.0,1744060577.2769642,9.021254539489746,1.4604730371918813e-10,1744060577.2769651,9.021254539489746,8.261683107326098,1744060577.2769663,9.021254539489746,1.1896823672769279e-20,1744060577.2769675,9.021254539489746,10,1744060577.2769687,9.021254539489746,0.0,1744060577.2769694,9.021254539489746,-22627416989.969524,1744060577.2769704,9.021254539489746,0.0,1744060577.2769716,9.021254539489746,28284271247.461903
+1744060577.2971284,9.041258573532104,-2.232603209381735,1744060577.2971308,9.041258573532104,-8.261683107326098,1744060577.2971337,9.041258573532104,0.0,1744060577.2971358,9.041258573532104,56568542496.923805,1744060577.2971373,9.041258573532104,0.0,1744060577.2971387,9.041258573532104,1.4604730371918813e-10,1744060577.2971401,9.041258573532104,8.261683107326098,1744060577.2971418,9.041258573532104,1.1896823672769279e-20,1744060577.297143,9.041258573532104,10,1744060577.2971442,9.041258573532104,0.0,1744060577.2971451,9.041258573532104,-22627416989.969524,1744060577.297146,9.041258573532104,0.0,1744060577.297147,9.041258573532104,28284271247.461903
+1744060577.3169649,9.06126356124878,-2.232603209381735,1744060577.3169668,9.06126356124878,-8.261683107326098,1744060577.3169687,9.06126356124878,0.0,1744060577.316971,9.06126356124878,56568542496.923805,1744060577.316972,9.06126356124878,0.0,1744060577.316973,9.06126356124878,1.4604730371918813e-10,1744060577.3169744,9.06126356124878,8.261683107326098,1744060577.3169754,9.06126356124878,1.1896823672769279e-20,1744060577.3169763,9.06126356124878,10,1744060577.3169773,9.06126356124878,0.0,1744060577.3169782,9.06126356124878,-22627416989.969524,1744060577.3169792,9.06126356124878,0.0,1744060577.3169801,9.06126356124878,28284271247.461903
+1744060577.336906,9.081238031387329,-2.232603209381735,1744060577.3369079,9.081238031387329,-8.261683107326098,1744060577.3369098,9.081238031387329,0.0,1744060577.336912,9.081238031387329,56568542496.923805,1744060577.3369129,9.081238031387329,0.0,1744060577.3369138,9.081238031387329,1.4604730371918813e-10,1744060577.3369153,9.081238031387329,8.261683107326098,1744060577.3369162,9.081238031387329,1.1896823672769279e-20,1744060577.3369172,9.081238031387329,10,1744060577.3369184,9.081238031387329,0.0,1744060577.336919,9.081238031387329,-22627416989.969524,1744060577.33692,9.081238031387329,0.0,1744060577.336921,9.081238031387329,28284271247.461903
+1744060577.357589,9.101288557052612,-2.232603209381735,1744060577.3575907,9.101288557052612,-8.261683107326098,1744060577.357593,9.101288557052612,0.0,1744060577.3575954,9.101288557052612,56568542496.923805,1744060577.3575964,9.101288557052612,0.0,1744060577.3575976,9.101288557052612,1.4604730371918813e-10,1744060577.3575993,9.101288557052612,8.261683107326098,1744060577.3576005,9.101288557052612,1.1896823672769279e-20,1744060577.3576021,9.101288557052612,10,1744060577.357603,9.101288557052612,0.0,1744060577.357604,9.101288557052612,-22627416989.969524,1744060577.3576052,9.101288557052612,0.0,1744060577.3576062,9.101288557052612,28284271247.461903
+1744060577.377305,9.121264457702637,-2.232603209381735,1744060577.3773072,9.121264457702637,-8.261683107326098,1744060577.377309,9.121264457702637,0.0,1744060577.3773115,9.121264457702637,56568542496.923805,1744060577.3773124,9.121264457702637,0.0,1744060577.3773136,9.121264457702637,1.4604730371918813e-10,1744060577.3773148,9.121264457702637,8.261683107326098,1744060577.3773158,9.121264457702637,1.1896823672769279e-20,1744060577.377317,9.121264457702637,10,1744060577.377318,9.121264457702637,0.0,1744060577.377319,9.121264457702637,-22627416989.969524,1744060577.3773203,9.121264457702637,0.0,1744060577.3773212,9.121264457702637,28284271247.461903
+1744060577.3969526,9.141225099563599,-2.232603209381735,1744060577.3969543,9.141225099563599,-8.261683107326098,1744060577.3969564,9.141225099563599,0.0,1744060577.3969584,9.141225099563599,56568542496.923805,1744060577.3969595,9.141225099563599,0.0,1744060577.3969607,9.141225099563599,1.4604730371918813e-10,1744060577.3969622,9.141225099563599,8.261683107326098,1744060577.3969631,9.141225099563599,1.1896823672769279e-20,1744060577.396964,9.141225099563599,10,1744060577.396965,9.141225099563599,0.0,1744060577.3969662,9.141225099563599,-22627416989.969524,1744060577.3969672,9.141225099563599,0.0,1744060577.3969681,9.141225099563599,28284271247.461903
+1744060577.4170604,9.161261320114136,-2.232603209381735,1744060577.4170623,9.161261320114136,-8.261683107326098,1744060577.4170644,9.161261320114136,0.0,1744060577.4170666,9.161261320114136,56568542496.923805,1744060577.4170675,9.161261320114136,0.0,1744060577.4170687,9.161261320114136,1.4604730371918813e-10,1744060577.4170702,9.161261320114136,8.261683107326098,1744060577.4170716,9.161261320114136,1.1896823672769279e-20,1744060577.4170725,9.161261320114136,10,1744060577.4170737,9.161261320114136,0.0,1744060577.4170747,9.161261320114136,-22627416989.969524,1744060577.4170756,9.161261320114136,0.0,1744060577.4170766,9.161261320114136,28284271247.461903
+1744060577.4369638,9.181224584579468,-2.232603209381735,1744060577.436967,9.181224584579468,-8.261683107326098,1744060577.4369705,9.181224584579468,0.0,1744060577.436973,9.181224584579468,56568542496.923805,1744060577.436974,9.181224584579468,0.0,1744060577.4369757,9.181224584579468,1.4604730371918813e-10,1744060577.4369767,9.181224584579468,8.261683107326098,1744060577.4369779,9.181224584579468,1.1896823672769279e-20,1744060577.436979,9.181224584579468,10,1744060577.43698,9.181224584579468,0.0,1744060577.4369984,9.181224584579468,-22627416989.969524,1744060577.4369993,9.181224584579468,0.0,1744060577.4370005,9.181224584579468,28284271247.461903
+1744060577.4575815,9.201274871826172,-2.232603209381735,1744060577.4575837,9.201274871826172,-8.261683107326098,1744060577.4575863,9.201274871826172,0.0,1744060577.4575884,9.201274871826172,56568542496.923805,1744060577.45759,9.201274871826172,0.0,1744060577.4575913,9.201274871826172,1.4604730371918813e-10,1744060577.4575925,9.201274871826172,8.261683107326098,1744060577.457594,9.201274871826172,1.1896823672769279e-20,1744060577.457595,9.201274871826172,10,1744060577.457596,9.201274871826172,0.0,1744060577.4575975,9.201274871826172,-22627416989.969524,1744060577.4575984,9.201274871826172,0.0,1744060577.4575996,9.201274871826172,28284271247.461903
+1744060577.4769564,9.221229314804077,-2.232603209381735,1744060577.4769585,9.221229314804077,-8.261683107326098,1744060577.4769604,9.221229314804077,0.0,1744060577.4769628,9.221229314804077,56568542496.923805,1744060577.4769638,9.221229314804077,0.0,1744060577.4769652,9.221229314804077,1.4604730371918813e-10,1744060577.4769664,9.221229314804077,8.261683107326098,1744060577.4769673,9.221229314804077,1.1896823672769279e-20,1744060577.4769685,9.221229314804077,10,1744060577.47697,9.221229314804077,0.0,1744060577.4769711,9.221229314804077,-22627416989.969524,1744060577.476973,9.221229314804077,0.0,1744060577.476975,9.221229314804077,28284271247.461903
+1744060577.4974613,9.241265058517456,-2.232603209381735,1744060577.497463,9.241265058517456,-8.261683107326098,1744060577.4974654,9.241265058517456,0.0,1744060577.4974673,9.241265058517456,56568542496.923805,1744060577.4974685,9.241265058517456,0.0,1744060577.4974697,9.241265058517456,1.4604730371918813e-10,1744060577.4974716,9.241265058517456,8.261683107326098,1744060577.4974728,9.241265058517456,1.1896823672769279e-20,1744060577.4974737,9.241265058517456,10,1744060577.4974751,9.241265058517456,0.0,1744060577.497476,9.241265058517456,-22627416989.969524,1744060577.497477,9.241265058517456,0.0,1744060577.4974782,9.241265058517456,28284271247.461903
+1744060577.517033,9.261274099349976,-2.232603209381735,1744060577.517035,9.261274099349976,-8.261683107326098,1744060577.5170372,9.261274099349976,0.0,1744060577.517039,9.261274099349976,56568542496.923805,1744060577.51704,9.261274099349976,0.0,1744060577.5170414,9.261274099349976,1.4604730371918813e-10,1744060577.5170426,9.261274099349976,8.261683107326098,1744060577.5170438,9.261274099349976,1.1896823672769279e-20,1744060577.5170448,9.261274099349976,10,1744060577.5170457,9.261274099349976,0.0,1744060577.5170467,9.261274099349976,-22627416989.969524,1744060577.5170476,9.261274099349976,0.0,1744060577.5170486,9.261274099349976,28284271247.461903
+1744060577.537035,9.281293392181396,-2.232603209381735,1744060577.537037,9.281293392181396,-8.261683107326098,1744060577.5370388,9.281293392181396,0.0,1744060577.537041,9.281293392181396,56568542496.923805,1744060577.537042,9.281293392181396,0.0,1744060577.537043,9.281293392181396,1.4604730371918813e-10,1744060577.5370443,9.281293392181396,8.261683107326098,1744060577.5370455,9.281293392181396,1.1896823672769279e-20,1744060577.5370467,9.281293392181396,10,1744060577.5370479,9.281293392181396,0.0,1744060577.5370488,9.281293392181396,-22627416989.969524,1744060577.53705,9.281293392181396,0.0,1744060577.537051,9.281293392181396,28284271247.461903
+1744060577.5573723,9.301230907440186,-2.232603209381735,1744060577.5573745,9.301230907440186,-8.261683107326098,1744060577.5573769,9.301230907440186,0.0,1744060577.557379,9.301230907440186,56568542496.923805,1744060577.5573802,9.301230907440186,0.0,1744060577.5573812,9.301230907440186,1.4604730371918813e-10,1744060577.5573823,9.301230907440186,8.261683107326098,1744060577.5573835,9.301230907440186,1.1896823672769279e-20,1744060577.5573852,9.301230907440186,10,1744060577.557386,9.301230907440186,0.0,1744060577.557387,9.301230907440186,-22627416989.969524,1744060577.557388,9.301230907440186,0.0,1744060577.5573888,9.301230907440186,28284271247.461903
+1744060577.5770514,9.321227073669434,-2.232603209381735,1744060577.577053,9.321227073669434,-8.261683107326098,1744060577.5770555,9.321227073669434,0.0,1744060577.5770576,9.321227073669434,56568542496.923805,1744060577.5770586,9.321227073669434,0.0,1744060577.5770597,9.321227073669434,1.4604730371918813e-10,1744060577.577061,9.321227073669434,8.261683107326098,1744060577.577062,9.321227073669434,1.1896823672769279e-20,1744060577.5770628,9.321227073669434,10,1744060577.577064,9.321227073669434,0.0,1744060577.5770648,9.321227073669434,-22627416989.969524,1744060577.5770657,9.321227073669434,0.0,1744060577.5770667,9.321227073669434,28284271247.461903
+1744060577.5969822,9.341246843338013,-2.232603209381735,1744060577.5969858,9.341246843338013,-8.261683107326098,1744060577.5969892,9.341246843338013,0.0,1744060577.5969923,9.341246843338013,56568542496.923805,1744060577.5970156,9.341246843338013,0.0,1744060577.5970175,9.341246843338013,1.4604730371918813e-10,1744060577.5970194,9.341246843338013,8.261683107326098,1744060577.597021,9.341246843338013,1.1896823672769279e-20,1744060577.597023,9.341246843338013,10,1744060577.5970247,9.341246843338013,0.0,1744060577.5970263,9.341246843338013,-22627416989.969524,1744060577.5970278,9.341246843338013,0.0,1744060577.5970294,9.341246843338013,28284271247.461903
+1744060577.6169586,9.36126446723938,-2.232603209381735,1744060577.6169605,9.36126446723938,-8.261683107326098,1744060577.6169627,9.36126446723938,0.0,1744060577.6169648,9.36126446723938,56568542496.923805,1744060577.6169655,9.36126446723938,0.0,1744060577.616967,9.36126446723938,1.4604730371918813e-10,1744060577.6169682,9.36126446723938,8.261683107326098,1744060577.616969,9.36126446723938,1.1896823672769279e-20,1744060577.6169703,9.36126446723938,10,1744060577.616971,9.36126446723938,0.0,1744060577.616972,9.36126446723938,-22627416989.969524,1744060577.6169732,9.36126446723938,0.0,1744060577.6169739,9.36126446723938,28284271247.461903
+1744060577.6369216,9.381229162216187,-2.232603209381735,1744060577.636923,9.381229162216187,-8.261683107326098,1744060577.6369252,9.381229162216187,0.0,1744060577.6369271,9.381229162216187,56568542496.923805,1744060577.6369283,9.381229162216187,0.0,1744060577.6369298,9.381229162216187,1.4604730371918813e-10,1744060577.6369307,9.381229162216187,8.261683107326098,1744060577.6369321,9.381229162216187,1.1896823672769279e-20,1744060577.6369333,9.381229162216187,10,1744060577.636934,9.381229162216187,0.0,1744060577.6369352,9.381229162216187,-22627416989.969524,1744060577.6369362,9.381229162216187,0.0,1744060577.636937,9.381229162216187,28284271247.461903
+1744060577.65727,9.40123176574707,-2.232603209381735,1744060577.6572719,9.40123176574707,-8.261683107326098,1744060577.6572745,9.40123176574707,0.0,1744060577.6572762,9.40123176574707,56568542496.923805,1744060577.657277,9.40123176574707,0.0,1744060577.6572785,9.40123176574707,1.4604730371918813e-10,1744060577.6572795,9.40123176574707,8.261683107326098,1744060577.6572804,9.40123176574707,1.1896823672769279e-20,1744060577.6572816,9.40123176574707,10,1744060577.6572826,9.40123176574707,0.0,1744060577.6572838,9.40123176574707,-22627416989.969524,1744060577.6572845,9.40123176574707,0.0,1744060577.6572857,9.40123176574707,28284271247.461903
+1744060577.6769354,9.421226739883423,-2.232603209381735,1744060577.676937,9.421226739883423,-8.261683107326098,1744060577.6769392,9.421226739883423,0.0,1744060577.6769414,9.421226739883423,56568542496.923805,1744060577.6769423,9.421226739883423,0.0,1744060577.6769433,9.421226739883423,1.4604730371918813e-10,1744060577.6769447,9.421226739883423,8.261683107326098,1744060577.6769457,9.421226739883423,1.1896823672769279e-20,1744060577.6769469,9.421226739883423,10,1744060577.6769476,9.421226739883423,0.0,1744060577.6769488,9.421226739883423,-22627416989.969524,1744060577.6769497,9.421226739883423,0.0,1744060577.6769507,9.421226739883423,28284271247.461903
+1744060577.6970441,9.441354036331177,-2.232603209381735,1744060577.697046,9.441354036331177,-8.261683107326098,1744060577.6970484,9.441354036331177,0.0,1744060577.6970503,9.441354036331177,56568542496.923805,1744060577.6970513,9.441354036331177,0.0,1744060577.6970525,9.441354036331177,1.4604730371918813e-10,1744060577.6970537,9.441354036331177,8.261683107326098,1744060577.6970549,9.441354036331177,1.1896823672769279e-20,1744060577.6970563,9.441354036331177,10,1744060577.697057,9.441354036331177,0.0,1744060577.697058,9.441354036331177,-22627416989.969524,1744060577.6970592,9.441354036331177,0.0,1744060577.6970599,9.441354036331177,28284271247.461903
+1744060577.7169445,9.461262226104736,-2.232603209381735,1744060577.716946,9.461262226104736,-8.261683107326098,1744060577.7169483,9.461262226104736,0.0,1744060577.7169502,9.461262226104736,56568542496.923805,1744060577.7169511,9.461262226104736,0.0,1744060577.7169526,9.461262226104736,1.4604730371918813e-10,1744060577.7169538,9.461262226104736,8.261683107326098,1744060577.716955,9.461262226104736,1.1896823672769279e-20,1744060577.7169561,9.461262226104736,10,1744060577.716957,9.461262226104736,0.0,1744060577.7169583,9.461262226104736,-22627416989.969524,1744060577.716959,9.461262226104736,0.0,1744060577.71696,9.461262226104736,28284271247.461903
+1744060577.7371461,9.481261968612671,-2.232603209381735,1744060577.7371478,9.481261968612671,-8.261683107326098,1744060577.7371678,9.481261968612671,0.0,1744060577.7371702,9.481261968612671,56568542496.923805,1744060577.7371712,9.481261968612671,0.0,1744060577.7371728,9.481261968612671,1.4604730371918813e-10,1744060577.737174,9.481261968612671,8.261683107326098,1744060577.737175,9.481261968612671,1.1896823672769279e-20,1744060577.7371762,9.481261968612671,10,1744060577.7371771,9.481261968612671,0.0,1744060577.737178,9.481261968612671,-22627416989.969524,1744060577.7371793,9.481261968612671,0.0,1744060577.7371805,9.481261968612671,28284271247.461903
+1744060577.7572064,9.501264333724976,-2.993345152438999,1744060577.7572083,9.501264333724976,-11.412905048041305,1744060577.7572103,9.501264333724976,0.0,1744060577.7572124,9.501264333724976,56568542496.923805,1744060577.757213,9.501264333724976,0.0,1744060577.7572145,9.501264333724976,2.0175356379489572e-10,1744060577.7572155,9.501264333724976,11.412905048041305,1744060577.7572165,9.501264333724976,1.6434583266278092e-20,1744060577.757218,9.501264333724976,10,1744060577.7572188,9.501264333724976,0.0,1744060577.7572196,9.501264333724976,-22627416989.969524,1744060577.7572205,9.501264333724976,0.0,1744060577.7572217,9.501264333724976,28284271247.461903
+1744060577.777059,9.521297931671143,-2.993345152438999,1744060577.7770607,9.521297931671143,-11.412905048041305,1744060577.7770631,9.521297931671143,0.0,1744060577.777065,9.521297931671143,56568542496.923805,1744060577.777066,9.521297931671143,0.0,1744060577.7770672,9.521297931671143,2.0175356379489572e-10,1744060577.7770684,9.521297931671143,11.412905048041305,1744060577.7770693,9.521297931671143,1.6434583266278092e-20,1744060577.7770703,9.521297931671143,10,1744060577.7770717,9.521297931671143,0.0,1744060577.7770724,9.521297931671143,-22627416989.969524,1744060577.7770734,9.521297931671143,0.0,1744060577.7770743,9.521297931671143,28284271247.461903
+1744060577.7975843,9.54126787185669,-2.993345152438999,1744060577.7975872,9.54126787185669,-11.412905048041305,1744060577.7975907,9.54126787185669,0.0,1744060577.7975943,9.54126787185669,56568542496.923805,1744060577.7975962,9.54126787185669,0.0,1744060577.7975984,9.54126787185669,2.0175356379489572e-10,1744060577.7976005,9.54126787185669,11.412905048041305,1744060577.797603,9.54126787185669,1.6434583266278092e-20,1744060577.7976048,9.54126787185669,10,1744060577.7976065,9.54126787185669,0.0,1744060577.7976081,9.54126787185669,-22627416989.969524,1744060577.79761,9.54126787185669,0.0,1744060577.797612,9.54126787185669,28284271247.461903
+1744060577.817042,9.561237335205078,-2.993345152438999,1744060577.817044,9.561237335205078,-11.412905048041305,1744060577.8170462,9.561237335205078,0.0,1744060577.8170483,9.561237335205078,56568542496.923805,1744060577.8170493,9.561237335205078,0.0,1744060577.8170507,9.561237335205078,2.0175356379489572e-10,1744060577.817052,9.561237335205078,11.412905048041305,1744060577.8170536,9.561237335205078,1.6434583266278092e-20,1744060577.8170552,9.561237335205078,10,1744060577.8170571,9.561237335205078,0.0,1744060577.8170583,9.561237335205078,-22627416989.969524,1744060577.8170607,9.561237335205078,0.0,1744060577.8170629,9.561237335205078,28284271247.461903
+1744060577.8369374,9.58125352859497,-2.993345152438999,1744060577.8369393,9.58125352859497,-11.412905048041305,1744060577.8369412,9.58125352859497,0.0,1744060577.8369434,9.58125352859497,56568542496.923805,1744060577.8369443,9.58125352859497,0.0,1744060577.8369458,9.58125352859497,2.0175356379489572e-10,1744060577.8369467,9.58125352859497,11.412905048041305,1744060577.836948,9.58125352859497,1.6434583266278092e-20,1744060577.836949,9.58125352859497,10,1744060577.83695,9.58125352859497,0.0,1744060577.836951,9.58125352859497,-22627416989.969524,1744060577.836952,9.58125352859497,0.0,1744060577.8369532,9.58125352859497,28284271247.461903
+1744060577.857412,9.601240396499634,-2.993345152438999,1744060577.857414,9.601240396499634,-11.412905048041305,1744060577.857416,9.601240396499634,0.0,1744060577.8574183,9.601240396499634,56568542496.923805,1744060577.857419,9.601240396499634,0.0,1744060577.8574202,9.601240396499634,2.0175356379489572e-10,1744060577.8574214,9.601240396499634,11.412905048041305,1744060577.8574226,9.601240396499634,1.6434583266278092e-20,1744060577.8574235,9.601240396499634,10,1744060577.8574247,9.601240396499634,0.0,1744060577.8574257,9.601240396499634,-22627416989.969524,1744060577.857427,9.601240396499634,0.0,1744060577.8574276,9.601240396499634,28284271247.461903
+1744060577.8769512,9.621253252029419,-2.993345152438999,1744060577.8769531,9.621253252029419,-11.412905048041305,1744060577.876955,9.621253252029419,0.0,1744060577.8769577,9.621253252029419,56568542496.923805,1744060577.8769586,9.621253252029419,0.0,1744060577.8769598,9.621253252029419,2.0175356379489572e-10,1744060577.876961,9.621253252029419,11.412905048041305,1744060577.876962,9.621253252029419,1.6434583266278092e-20,1744060577.8769631,9.621253252029419,10,1744060577.876964,9.621253252029419,0.0,1744060577.8769653,9.621253252029419,-22627416989.969524,1744060577.8769665,9.621253252029419,0.0,1744060577.8769674,9.621253252029419,28284271247.461903
+1744060577.898061,9.641286134719849,-2.993345152438999,1744060577.8980634,9.641286134719849,-11.412905048041305,1744060577.8980656,9.641286134719849,0.0,1744060577.898068,9.641286134719849,56568542496.923805,1744060577.898069,9.641286134719849,0.0,1744060577.8980703,9.641286134719849,2.0175356379489572e-10,1744060577.8980718,9.641286134719849,11.412905048041305,1744060577.8980727,9.641286134719849,1.6434583266278092e-20,1744060577.8980742,9.641286134719849,10,1744060577.898075,9.641286134719849,0.0,1744060577.898076,9.641286134719849,-22627416989.969524,1744060577.8980772,9.641286134719849,0.0,1744060577.8980782,9.641286134719849,28284271247.461903
+1744060577.9170442,9.661231279373169,-2.993345152438999,1744060577.9170468,9.661231279373169,-11.412905048041305,1744060577.91705,9.661231279373169,0.0,1744060577.9170527,9.661231279373169,56568542496.923805,1744060577.9170542,9.661231279373169,0.0,1744060577.917056,9.661231279373169,2.0175356379489572e-10,1744060577.9170578,9.661231279373169,11.412905048041305,1744060577.9170597,9.661231279373169,1.6434583266278092e-20,1744060577.917061,9.661231279373169,10,1744060577.9170628,9.661231279373169,0.0,1744060577.9170642,9.661231279373169,-22627416989.969524,1744060577.9170656,9.661231279373169,0.0,1744060577.917067,9.661231279373169,28284271247.461903
+1744060577.9368944,9.681224584579468,-2.993345152438999,1744060577.9368966,9.681224584579468,-11.412905048041305,1744060577.9368985,9.681224584579468,0.0,1744060577.9369009,9.681224584579468,56568542496.923805,1744060577.9369018,9.681224584579468,0.0,1744060577.936903,9.681224584579468,2.0175356379489572e-10,1744060577.9369042,9.681224584579468,11.412905048041305,1744060577.9369051,9.681224584579468,1.6434583266278092e-20,1744060577.9369063,9.681224584579468,10,1744060577.9369073,9.681224584579468,0.0,1744060577.9369082,9.681224584579468,-22627416989.969524,1744060577.9369097,9.681224584579468,0.0,1744060577.9369106,9.681224584579468,28284271247.461903
+1744060577.9576447,9.701297521591187,-2.993345152438999,1744060577.9576466,9.701297521591187,-11.412905048041305,1744060577.9576488,9.701297521591187,0.0,1744060577.9576507,9.701297521591187,56568542496.923805,1744060577.9576516,9.701297521591187,0.0,1744060577.957653,9.701297521591187,2.0175356379489572e-10,1744060577.957654,9.701297521591187,11.412905048041305,1744060577.9576552,9.701297521591187,1.6434583266278092e-20,1744060577.9576564,9.701297521591187,10,1744060577.9576573,9.701297521591187,0.0,1744060577.9576583,9.701297521591187,-22627416989.969524,1744060577.9576595,9.701297521591187,0.0,1744060577.9576602,9.701297521591187,28284271247.461903
+1744060577.976969,9.721228122711182,-2.993345152438999,1744060577.9769707,9.721228122711182,-11.412905048041305,1744060577.976973,9.721228122711182,0.0,1744060577.9769752,9.721228122711182,56568542496.923805,1744060577.9769762,9.721228122711182,0.0,1744060577.9769773,9.721228122711182,2.0175356379489572e-10,1744060577.9769785,9.721228122711182,11.412905048041305,1744060577.9769797,9.721228122711182,1.6434583266278092e-20,1744060577.976981,9.721228122711182,10,1744060577.9769819,9.721228122711182,0.0,1744060577.9769828,9.721228122711182,-22627416989.969524,1744060577.9769838,9.721228122711182,0.0,1744060577.9769847,9.721228122711182,28284271247.461903
+1744060577.9983854,9.741287469863892,-2.993345152438999,1744060577.9984086,9.741287469863892,-11.412905048041305,1744060577.998411,9.741287469863892,0.0,1744060577.998413,9.741287469863892,56568542496.923805,1744060577.9984143,9.741287469863892,0.0,1744060577.9984157,9.741287469863892,2.0175356379489572e-10,1744060577.998417,9.741287469863892,11.412905048041305,1744060577.998418,9.741287469863892,1.6434583266278092e-20,1744060577.9984195,9.741287469863892,10,1744060577.9984205,9.741287469863892,0.0,1744060577.9984214,9.741287469863892,-22627416989.969524,1744060577.9984226,9.741287469863892,0.0,1744060577.9984236,9.741287469863892,28284271247.461903
+1744060578.0174444,9.761290550231934,-2.993345152438999,1744060578.0174465,9.761290550231934,-11.412905048041305,1744060578.0174491,9.761290550231934,0.0,1744060578.0174515,9.761290550231934,56568542496.923805,1744060578.0174527,9.761290550231934,0.0,1744060578.0174544,9.761290550231934,2.0175356379489572e-10,1744060578.0174556,9.761290550231934,11.412905048041305,1744060578.0174575,9.761290550231934,1.6434583266278092e-20,1744060578.0174594,9.761290550231934,10,1744060578.017461,9.761290550231934,0.0,1744060578.0174627,9.761290550231934,-22627416989.969524,1744060578.0174646,9.761290550231934,0.0,1744060578.0174665,9.761290550231934,28284271247.461903
+1744060578.0369303,9.781224012374878,-2.993345152438999,1744060578.0369318,9.781224012374878,-11.412905048041305,1744060578.0369341,9.781224012374878,0.0,1744060578.0369363,9.781224012374878,56568542496.923805,1744060578.036937,9.781224012374878,0.0,1744060578.0369382,9.781224012374878,2.0175356379489572e-10,1744060578.0369399,9.781224012374878,11.412905048041305,1744060578.0369408,9.781224012374878,1.6434583266278092e-20,1744060578.036942,9.781224012374878,10,1744060578.0369432,9.781224012374878,0.0,1744060578.036944,9.781224012374878,-22627416989.969524,1744060578.0369449,9.781224012374878,0.0,1744060578.0369458,9.781224012374878,28284271247.461903
+1744060578.0574484,9.801281690597534,-2.993345152438999,1744060578.057451,9.801281690597534,-11.412905048041305,1744060578.0574543,9.801281690597534,0.0,1744060578.0574577,9.801281690597534,56568542496.923805,1744060578.0574594,9.801281690597534,0.0,1744060578.0574617,9.801281690597534,2.0175356379489572e-10,1744060578.0574634,9.801281690597534,11.412905048041305,1744060578.0574644,9.801281690597534,1.6434583266278092e-20,1744060578.0574656,9.801281690597534,10,1744060578.0574665,9.801281690597534,0.0,1744060578.0574675,9.801281690597534,-22627416989.969524,1744060578.0574684,9.801281690597534,0.0,1744060578.0574691,9.801281690597534,28284271247.461903
+1744060578.0769434,9.821226596832275,-2.993345152438999,1744060578.0769448,9.821226596832275,-11.412905048041305,1744060578.0769472,9.821226596832275,0.0,1744060578.0769494,9.821226596832275,56568542496.923805,1744060578.0769503,9.821226596832275,0.0,1744060578.0769515,9.821226596832275,2.0175356379489572e-10,1744060578.076953,9.821226596832275,11.412905048041305,1744060578.0769541,9.821226596832275,1.6434583266278092e-20,1744060578.076955,9.821226596832275,10,1744060578.0769563,9.821226596832275,0.0,1744060578.0769572,9.821226596832275,-22627416989.969524,1744060578.0769582,9.821226596832275,0.0,1744060578.0769591,9.821226596832275,28284271247.461903
+1744060578.0969367,9.84123158454895,-2.993345152438999,1744060578.0969386,9.84123158454895,-11.412905048041305,1744060578.0969408,9.84123158454895,0.0,1744060578.096943,9.84123158454895,56568542496.923805,1744060578.0969439,9.84123158454895,0.0,1744060578.0969448,9.84123158454895,2.0175356379489572e-10,1744060578.0969465,9.84123158454895,11.412905048041305,1744060578.0969474,9.84123158454895,1.6434583266278092e-20,1744060578.0969486,9.84123158454895,10,1744060578.0969498,9.84123158454895,0.0,1744060578.0969505,9.84123158454895,-22627416989.969524,1744060578.0969515,9.84123158454895,0.0,1744060578.0969527,9.84123158454895,28284271247.461903
+1744060578.1169372,9.861228466033936,-2.993345152438999,1744060578.116939,9.861228466033936,-11.412905048041305,1744060578.116941,9.861228466033936,0.0,1744060578.1169431,9.861228466033936,56568542496.923805,1744060578.116944,9.861228466033936,0.0,1744060578.1169455,9.861228466033936,2.0175356379489572e-10,1744060578.1169465,9.861228466033936,11.412905048041305,1744060578.1169477,9.861228466033936,1.6434583266278092e-20,1744060578.1169488,9.861228466033936,10,1744060578.1169498,9.861228466033936,0.0,1744060578.1169508,9.861228466033936,-22627416989.969524,1744060578.1169515,9.861228466033936,0.0,1744060578.1169527,9.861228466033936,28284271247.461903
+1744060578.136863,9.881223440170288,-2.993345152438999,1744060578.1368651,9.881223440170288,-11.412905048041305,1744060578.136867,9.881223440170288,0.0,1744060578.1368692,9.881223440170288,56568542496.923805,1744060578.1368701,9.881223440170288,0.0,1744060578.136871,9.881223440170288,2.0175356379489572e-10,1744060578.1368725,9.881223440170288,11.412905048041305,1744060578.1368735,9.881223440170288,1.6434583266278092e-20,1744060578.1368747,9.881223440170288,10,1744060578.1368759,9.881223440170288,0.0,1744060578.1368766,9.881223440170288,-22627416989.969524,1744060578.1368775,9.881223440170288,0.0,1744060578.1368783,9.881223440170288,28284271247.461903
+1744060578.1573524,9.901278257369995,-2.993345152438999,1744060578.1573544,9.901278257369995,-11.412905048041305,1744060578.1573565,9.901278257369995,0.0,1744060578.157359,9.901278257369995,56568542496.923805,1744060578.1573598,9.901278257369995,0.0,1744060578.1573613,9.901278257369995,2.0175356379489572e-10,1744060578.1573622,9.901278257369995,11.412905048041305,1744060578.1573634,9.901278257369995,1.6434583266278092e-20,1744060578.1573644,9.901278257369995,10,1744060578.1573656,9.901278257369995,0.0,1744060578.1573665,9.901278257369995,-22627416989.969524,1744060578.1573675,9.901278257369995,0.0,1744060578.1573687,9.901278257369995,28284271247.461903
+1744060578.1769483,9.921226739883423,-2.993345152438999,1744060578.1769502,9.921226739883423,-11.412905048041305,1744060578.1769524,9.921226739883423,0.0,1744060578.1769543,9.921226739883423,56568542496.923805,1744060578.1769555,9.921226739883423,0.0,1744060578.1769567,9.921226739883423,2.0175356379489572e-10,1744060578.1769578,9.921226739883423,11.412905048041305,1744060578.1769593,9.921226739883423,1.6434583266278092e-20,1744060578.1769602,9.921226739883423,10,1744060578.1769612,9.921226739883423,0.0,1744060578.1769621,9.921226739883423,-22627416989.969524,1744060578.176963,9.921226739883423,0.0,1744060578.176964,9.921226739883423,28284271247.461903
+1744060578.1971917,9.941286563873291,-2.993345152438999,1744060578.1971936,9.941286563873291,-11.412905048041305,1744060578.197196,9.941286563873291,0.0,1744060578.1971986,9.941286563873291,56568542496.923805,1744060578.1971996,9.941286563873291,0.0,1744060578.197201,9.941286563873291,2.0175356379489572e-10,1744060578.1972022,9.941286563873291,11.412905048041305,1744060578.1972036,9.941286563873291,1.6434583266278092e-20,1744060578.197205,9.941286563873291,10,1744060578.1972063,9.941286563873291,0.0,1744060578.197207,9.941286563873291,-22627416989.969524,1744060578.1972084,9.941286563873291,0.0,1744060578.1972094,9.941286563873291,28284271247.461903
+1744060578.216952,9.961262464523315,-2.993345152438999,1744060578.2169538,9.961262464523315,-11.412905048041305,1744060578.216956,9.961262464523315,0.0,1744060578.2169583,9.961262464523315,56568542496.923805,1744060578.2169592,9.961262464523315,0.0,1744060578.2169604,9.961262464523315,2.0175356379489572e-10,1744060578.2169616,9.961262464523315,11.412905048041305,1744060578.2169626,9.961262464523315,1.6434583266278092e-20,1744060578.2169635,9.961262464523315,10,1744060578.2169647,9.961262464523315,0.0,1744060578.2169654,9.961262464523315,-22627416989.969524,1744060578.2169664,9.961262464523315,0.0,1744060578.2169673,9.961262464523315,28284271247.461903
+1744060578.2373827,9.981268167495728,-2.993345152438999,1744060578.2373846,9.981268167495728,-11.412905048041305,1744060578.2373867,9.981268167495728,0.0,1744060578.237389,9.981268167495728,56568542496.923805,1744060578.23739,9.981268167495728,0.0,1744060578.2373917,9.981268167495728,2.0175356379489572e-10,1744060578.237393,9.981268167495728,11.412905048041305,1744060578.2373939,9.981268167495728,1.6434583266278092e-20,1744060578.2373955,9.981268167495728,10,1744060578.2373967,9.981268167495728,0.0,1744060578.2373977,9.981268167495728,-22627416989.969524,1744060578.2373989,9.981268167495728,0.0,1744060578.2373998,9.981268167495728,28284271247.461903
+1744060578.2582252,10.001306056976318,-3.7327906412808582,1744060578.258228,10.001306056976318,-14.862269182151813,1744060578.2582304,10.001306056976318,0.0,1744060578.2582333,10.001306056976318,56568542496.923805,1744060578.2582343,10.001306056976318,0.0,1744060578.2582362,10.001306056976318,2.6273028303635906e-10,1744060578.2582376,10.001306056976318,14.862269182151813,1744060578.258239,10.001306056976318,2.1401667617960817e-20,1744060578.2582402,10.001306056976318,10,1744060578.2582412,10.001306056976318,0.0,1744060578.2582424,10.001306056976318,-22627416989.969524,1744060578.2582443,10.001306056976318,0.0,1744060578.2582462,10.001306056976318,28284271247.461903
+1744060578.2769918,10.021231174468994,-3.7327906412808582,1744060578.2769935,10.021231174468994,-14.862269182151813,1744060578.276996,10.021231174468994,0.0,1744060578.2769978,10.021231174468994,56568542496.923805,1744060578.276999,10.021231174468994,0.0,1744060578.2770004,10.021231174468994,2.6273028303635906e-10,1744060578.2770014,10.021231174468994,14.862269182151813,1744060578.2770026,10.021231174468994,2.1401667617960817e-20,1744060578.2770038,10.021231174468994,10,1744060578.2770047,10.021231174468994,0.0,1744060578.277006,10.021231174468994,-22627416989.969524,1744060578.2770069,10.021231174468994,0.0,1744060578.2770078,10.021231174468994,28284271247.461903
+1744060578.296988,10.041262865066528,-3.7327906412808582,1744060578.2969897,10.041262865066528,-14.862269182151813,1744060578.296992,10.041262865066528,0.0,1744060578.296994,10.041262865066528,56568542496.923805,1744060578.2969952,10.041262865066528,0.0,1744060578.2969966,10.041262865066528,2.6273028303635906e-10,1744060578.2969978,10.041262865066528,14.862269182151813,1744060578.296999,10.041262865066528,2.1401667617960817e-20,1744060578.297,10.041262865066528,10,1744060578.297001,10.041262865066528,0.0,1744060578.297002,10.041262865066528,-22627416989.969524,1744060578.297003,10.041262865066528,0.0,1744060578.297004,10.041262865066528,28284271247.461903
+1744060578.316957,10.061259984970093,-3.7327906412808582,1744060578.3169587,10.061259984970093,-14.862269182151813,1744060578.3169608,10.061259984970093,0.0,1744060578.3169627,10.061259984970093,56568542496.923805,1744060578.316964,10.061259984970093,0.0,1744060578.3169653,10.061259984970093,2.6273028303635906e-10,1744060578.3169663,10.061259984970093,14.862269182151813,1744060578.3169675,10.061259984970093,2.1401667617960817e-20,1744060578.3169687,10.061259984970093,10,1744060578.3169696,10.061259984970093,0.0,1744060578.3169708,10.061259984970093,-22627416989.969524,1744060578.3169718,10.061259984970093,0.0,1744060578.3169727,10.061259984970093,28284271247.461903
+1744060578.3369465,10.081227540969849,-3.7327906412808582,1744060578.336948,10.081227540969849,-14.862269182151813,1744060578.3369503,10.081227540969849,0.0,1744060578.3369522,10.081227540969849,56568542496.923805,1744060578.3369534,10.081227540969849,0.0,1744060578.3369546,10.081227540969849,2.6273028303635906e-10,1744060578.3369555,10.081227540969849,14.862269182151813,1744060578.336957,10.081227540969849,2.1401667617960817e-20,1744060578.3369582,10.081227540969849,10,1744060578.3369591,10.081227540969849,0.0,1744060578.3369603,10.081227540969849,-22627416989.969524,1744060578.336961,10.081227540969849,0.0,1744060578.336962,10.081227540969849,28284271247.461903
+1744060578.3572938,10.10123348236084,-3.7327906412808582,1744060578.3572955,10.10123348236084,-14.862269182151813,1744060578.3572974,10.10123348236084,0.0,1744060578.3572996,10.10123348236084,56568542496.923805,1744060578.3573005,10.10123348236084,0.0,1744060578.3573017,10.10123348236084,2.6273028303635906e-10,1744060578.3573027,10.10123348236084,14.862269182151813,1744060578.3573039,10.10123348236084,2.1401667617960817e-20,1744060578.357305,10.10123348236084,10,1744060578.357306,10.10123348236084,0.0,1744060578.3573072,10.10123348236084,-22627416989.969524,1744060578.3573081,10.10123348236084,0.0,1744060578.357309,10.10123348236084,28284271247.461903
+1744060578.3770368,10.12121844291687,-3.7327906412808582,1744060578.3770394,10.12121844291687,-14.862269182151813,1744060578.3770418,10.12121844291687,0.0,1744060578.3770442,10.12121844291687,56568542496.923805,1744060578.3770452,10.12121844291687,0.0,1744060578.3770466,10.12121844291687,2.6273028303635906e-10,1744060578.3770478,10.12121844291687,14.862269182151813,1744060578.377049,10.12121844291687,2.1401667617960817e-20,1744060578.3770502,10.12121844291687,10,1744060578.377051,10.12121844291687,0.0,1744060578.377052,10.12121844291687,-22627416989.969524,1744060578.3770533,10.12121844291687,0.0,1744060578.377054,10.12121844291687,28284271247.461903
+1744060578.3970113,10.141260623931885,-3.7327906412808582,1744060578.3970132,10.141260623931885,-14.862269182151813,1744060578.397016,10.141260623931885,0.0,1744060578.3970187,10.141260623931885,56568542496.923805,1744060578.3970199,10.141260623931885,0.0,1744060578.3970218,10.141260623931885,2.6273028303635906e-10,1744060578.3970232,10.141260623931885,14.862269182151813,1744060578.3970249,10.141260623931885,2.1401667617960817e-20,1744060578.397026,10.141260623931885,10,1744060578.397027,10.141260623931885,0.0,1744060578.3970282,10.141260623931885,-22627416989.969524,1744060578.3970292,10.141260623931885,0.0,1744060578.3970304,10.141260623931885,28284271247.461903
+1744060578.416963,10.161274671554565,-3.7327906412808582,1744060578.4169648,10.161274671554565,-14.862269182151813,1744060578.4169672,10.161274671554565,0.0,1744060578.4169693,10.161274671554565,56568542496.923805,1744060578.4169703,10.161274671554565,0.0,1744060578.4169714,10.161274671554565,2.6273028303635906e-10,1744060578.4169729,10.161274671554565,14.862269182151813,1744060578.4169738,10.161274671554565,2.1401667617960817e-20,1744060578.4169748,10.161274671554565,10,1744060578.416976,10.161274671554565,0.0,1744060578.416977,10.161274671554565,-22627416989.969524,1744060578.416978,10.161274671554565,0.0,1744060578.4169788,10.161274671554565,28284271247.461903
+1744060578.4369662,10.181262254714966,-3.7327906412808582,1744060578.436968,10.181262254714966,-14.862269182151813,1744060578.4369702,10.181262254714966,0.0,1744060578.4369724,10.181262254714966,56568542496.923805,1744060578.4369733,10.181262254714966,0.0,1744060578.4369743,10.181262254714966,2.6273028303635906e-10,1744060578.4369757,10.181262254714966,14.862269182151813,1744060578.4369767,10.181262254714966,2.1401667617960817e-20,1744060578.4369776,10.181262254714966,10,1744060578.4369786,10.181262254714966,0.0,1744060578.4369798,10.181262254714966,-22627416989.969524,1744060578.4369805,10.181262254714966,0.0,1744060578.4369814,10.181262254714966,28284271247.461903
+1744060578.45717,10.201228380203247,-3.7327906412808582,1744060578.4571717,10.201228380203247,-14.862269182151813,1744060578.4571736,10.201228380203247,0.0,1744060578.4571755,10.201228380203247,56568542496.923805,1744060578.4571767,10.201228380203247,0.0,1744060578.4571779,10.201228380203247,2.6273028303635906e-10,1744060578.457179,10.201228380203247,14.862269182151813,1744060578.4571803,10.201228380203247,2.1401667617960817e-20,1744060578.4571815,10.201228380203247,10,1744060578.4571824,10.201228380203247,0.0,1744060578.4571836,10.201228380203247,-22627416989.969524,1744060578.4571846,10.201228380203247,0.0,1744060578.4571853,10.201228380203247,28284271247.461903
+1744060578.4769218,10.22122836112976,-3.7327906412808582,1744060578.476924,10.22122836112976,-14.862269182151813,1744060578.4769258,10.22122836112976,0.0,1744060578.476928,10.22122836112976,56568542496.923805,1744060578.476929,10.22122836112976,0.0,1744060578.4769304,10.22122836112976,2.6273028303635906e-10,1744060578.4769316,10.22122836112976,14.862269182151813,1744060578.4769328,10.22122836112976,2.1401667617960817e-20,1744060578.476934,10.22122836112976,10,1744060578.476935,10.22122836112976,0.0,1744060578.4769359,10.22122836112976,-22627416989.969524,1744060578.4769368,10.22122836112976,0.0,1744060578.4769378,10.22122836112976,28284271247.461903
+1744060578.4972806,10.241278171539307,-3.7327906412808582,1744060578.4972825,10.241278171539307,-14.862269182151813,1744060578.4972851,10.241278171539307,0.0,1744060578.4972875,10.241278171539307,56568542496.923805,1744060578.4972885,10.241278171539307,0.0,1744060578.4972901,10.241278171539307,2.6273028303635906e-10,1744060578.4972916,10.241278171539307,14.862269182151813,1744060578.497293,10.241278171539307,2.1401667617960817e-20,1744060578.4972944,10.241278171539307,10,1744060578.4972954,10.241278171539307,0.0,1744060578.4972963,10.241278171539307,-22627416989.969524,1744060578.4972975,10.241278171539307,0.0,1744060578.4972985,10.241278171539307,28284271247.461903
+1744060578.5168965,10.261250972747803,-3.7327906412808582,1744060578.5168984,10.261250972747803,-14.862269182151813,1744060578.5169003,10.261250972747803,0.0,1744060578.5169027,10.261250972747803,56568542496.923805,1744060578.5169036,10.261250972747803,0.0,1744060578.516905,10.261250972747803,2.6273028303635906e-10,1744060578.5169063,10.261250972747803,14.862269182151813,1744060578.5169075,10.261250972747803,2.1401667617960817e-20,1744060578.516909,10.261250972747803,10,1744060578.5169098,10.261250972747803,0.0,1744060578.5169106,10.261250972747803,-22627416989.969524,1744060578.5169115,10.261250972747803,0.0,1744060578.5169127,10.261250972747803,28284271247.461903
+1744060578.5369549,10.281259059906006,-3.7327906412808582,1744060578.536957,10.281259059906006,-14.862269182151813,1744060578.5369592,10.281259059906006,0.0,1744060578.5369616,10.281259059906006,56568542496.923805,1744060578.5369625,10.281259059906006,0.0,1744060578.536964,10.281259059906006,2.6273028303635906e-10,1744060578.5369651,10.281259059906006,14.862269182151813,1744060578.536966,10.281259059906006,2.1401667617960817e-20,1744060578.5369675,10.281259059906006,10,1744060578.5369685,10.281259059906006,0.0,1744060578.5369694,10.281259059906006,-22627416989.969524,1744060578.5369701,10.281259059906006,0.0,1744060578.5369713,10.281259059906006,28284271247.461903
+1744060578.5572078,10.301260232925415,-3.7327906412808582,1744060578.5572095,10.301260232925415,-14.862269182151813,1744060578.5572116,10.301260232925415,0.0,1744060578.557214,10.301260232925415,56568542496.923805,1744060578.557215,10.301260232925415,0.0,1744060578.557216,10.301260232925415,2.6273028303635906e-10,1744060578.5572174,10.301260232925415,14.862269182151813,1744060578.5572186,10.301260232925415,2.1401667617960817e-20,1744060578.5572197,10.301260232925415,10,1744060578.557221,10.301260232925415,0.0,1744060578.557222,10.301260232925415,-22627416989.969524,1744060578.5572228,10.301260232925415,0.0,1744060578.5572238,10.301260232925415,28284271247.461903
+1744060578.5768864,10.321218252182007,-3.7327906412808582,1744060578.576888,10.321218252182007,-14.862269182151813,1744060578.5768905,10.321218252182007,0.0,1744060578.5768924,10.321218252182007,56568542496.923805,1744060578.5768933,10.321218252182007,0.0,1744060578.5768948,10.321218252182007,2.6273028303635906e-10,1744060578.5768957,10.321218252182007,14.862269182151813,1744060578.576897,10.321218252182007,2.1401667617960817e-20,1744060578.576898,10.321218252182007,10,1744060578.576899,10.321218252182007,0.0,1744060578.5768998,10.321218252182007,-22627416989.969524,1744060578.576901,10.321218252182007,0.0,1744060578.576902,10.321218252182007,28284271247.461903
+1744060578.5969815,10.341263771057129,-3.7327906412808582,1744060578.5969837,10.341263771057129,-14.862269182151813,1744060578.5969858,10.341263771057129,0.0,1744060578.596988,10.341263771057129,56568542496.923805,1744060578.596989,10.341263771057129,0.0,1744060578.5969903,10.341263771057129,2.6273028303635906e-10,1744060578.5969915,10.341263771057129,14.862269182151813,1744060578.5969925,10.341263771057129,2.1401667617960817e-20,1744060578.5969937,10.341263771057129,10,1744060578.5969946,10.341263771057129,0.0,1744060578.5969956,10.341263771057129,-22627416989.969524,1744060578.5969965,10.341263771057129,0.0,1744060578.5969973,10.341263771057129,28284271247.461903
+1744060578.6168725,10.361222743988037,-3.7327906412808582,1744060578.6168742,10.361222743988037,-14.862269182151813,1744060578.6168766,10.361222743988037,0.0,1744060578.6168785,10.361222743988037,56568542496.923805,1744060578.6168797,10.361222743988037,0.0,1744060578.616881,10.361222743988037,2.6273028303635906e-10,1744060578.616882,10.361222743988037,14.862269182151813,1744060578.6168833,10.361222743988037,2.1401667617960817e-20,1744060578.6168845,10.361222743988037,10,1744060578.6168852,10.361222743988037,0.0,1744060578.6168864,10.361222743988037,-22627416989.969524,1744060578.6168873,10.361222743988037,0.0,1744060578.6168883,10.361222743988037,28284271247.461903
+1744060578.6369278,10.381243228912354,-3.7327906412808582,1744060578.6369295,10.381243228912354,-14.862269182151813,1744060578.6369317,10.381243228912354,0.0,1744060578.6369338,10.381243228912354,56568542496.923805,1744060578.636935,10.381243228912354,0.0,1744060578.6369362,10.381243228912354,2.6273028303635906e-10,1744060578.6369371,10.381243228912354,14.862269182151813,1744060578.6369386,10.381243228912354,2.1401667617960817e-20,1744060578.6369395,10.381243228912354,10,1744060578.6369405,10.381243228912354,0.0,1744060578.6369412,10.381243228912354,-22627416989.969524,1744060578.6369424,10.381243228912354,0.0,1744060578.6369433,10.381243228912354,28284271247.461903
+1744060578.6573012,10.401266813278198,-3.7327906412808582,1744060578.6573036,10.401266813278198,-14.862269182151813,1744060578.657306,10.401266813278198,0.0,1744060578.657308,10.401266813278198,56568542496.923805,1744060578.6573093,10.401266813278198,0.0,1744060578.6573105,10.401266813278198,2.6273028303635906e-10,1744060578.6573117,10.401266813278198,14.862269182151813,1744060578.657313,10.401266813278198,2.1401667617960817e-20,1744060578.6573143,10.401266813278198,10,1744060578.6573155,10.401266813278198,0.0,1744060578.6573167,10.401266813278198,-22627416989.969524,1744060578.6573176,10.401266813278198,0.0,1744060578.6573186,10.401266813278198,28284271247.461903
+1744060578.6769018,10.42125153541565,-3.7327906412808582,1744060578.6769037,10.42125153541565,-14.862269182151813,1744060578.6769056,10.42125153541565,0.0,1744060578.676908,10.42125153541565,56568542496.923805,1744060578.676909,10.42125153541565,0.0,1744060578.6769102,10.42125153541565,2.6273028303635906e-10,1744060578.6769116,10.42125153541565,14.862269182151813,1744060578.6769125,10.42125153541565,2.1401667617960817e-20,1744060578.6769137,10.42125153541565,10,1744060578.6769147,10.42125153541565,0.0,1744060578.6769156,10.42125153541565,-22627416989.969524,1744060578.6769168,10.42125153541565,0.0,1744060578.6769178,10.42125153541565,28284271247.461903
+1744060578.6969955,10.441227912902832,-3.7327906412808582,1744060578.6969984,10.441227912902832,-14.862269182151813,1744060578.6970015,10.441227912902832,0.0,1744060578.6970046,10.441227912902832,56568542496.923805,1744060578.6970062,10.441227912902832,0.0,1744060578.6970084,10.441227912902832,2.6273028303635906e-10,1744060578.6970098,10.441227912902832,14.862269182151813,1744060578.697011,10.441227912902832,2.1401667617960817e-20,1744060578.697012,10.441227912902832,10,1744060578.697013,10.441227912902832,0.0,1744060578.6970139,10.441227912902832,-22627416989.969524,1744060578.6970148,10.441227912902832,0.0,1744060578.6970158,10.441227912902832,28284271247.461903
+1744060578.7170558,10.461261510848999,-3.7327906412808582,1744060578.7170575,10.461261510848999,-14.862269182151813,1744060578.7170599,10.461261510848999,0.0,1744060578.7170622,10.461261510848999,56568542496.923805,1744060578.7170632,10.461261510848999,0.0,1744060578.7170644,10.461261510848999,2.6273028303635906e-10,1744060578.7170656,10.461261510848999,14.862269182151813,1744060578.7170665,10.461261510848999,2.1401667617960817e-20,1744060578.7170677,10.461261510848999,10,1744060578.717069,10.461261510848999,0.0,1744060578.7170699,10.461261510848999,-22627416989.969524,1744060578.7170708,10.461261510848999,0.0,1744060578.7170718,10.461261510848999,28284271247.461903
+1744060578.7369595,10.48127031326294,-3.7327906412808582,1744060578.7369614,10.48127031326294,-14.862269182151813,1744060578.7369633,10.48127031326294,0.0,1744060578.7369654,10.48127031326294,56568542496.923805,1744060578.7369664,10.48127031326294,0.0,1744060578.7369676,10.48127031326294,2.6273028303635906e-10,1744060578.7369688,10.48127031326294,14.862269182151813,1744060578.7369697,10.48127031326294,2.1401667617960817e-20,1744060578.736971,10.48127031326294,10,1744060578.7369719,10.48127031326294,0.0,1744060578.7369728,10.48127031326294,-22627416989.969524,1744060578.7369738,10.48127031326294,0.0,1744060578.736975,10.48127031326294,28284271247.461903
+1744060578.7576969,10.501290321350098,-4.4691444582273405,1744060578.7576988,10.501290321350098,-18.277839715685364,1744060578.7577014,10.501290321350098,0.0,1744060578.7577035,10.501290321350098,56568542496.923805,1744060578.7577045,10.501290321350098,0.0,1744060578.7577057,10.501290321350098,3.231096101730973e-10,1744060578.7577066,10.501290321350098,18.277839715685364,1744060578.7577083,10.501290321350098,2.6320089184567022e-20,1744060578.7577095,10.501290321350098,10,1744060578.7577107,10.501290321350098,0.0,1744060578.7577116,10.501290321350098,-22627416989.969524,1744060578.757713,10.501290321350098,0.0,1744060578.757714,10.501290321350098,28284271247.461903
+1744060578.776958,10.521260261535645,-4.4691444582273405,1744060578.7769597,10.521260261535645,-18.277839715685364,1744060578.7769618,10.521260261535645,0.0,1744060578.7769642,10.521260261535645,56568542496.923805,1744060578.776965,10.521260261535645,0.0,1744060578.776966,10.521260261535645,3.231096101730973e-10,1744060578.7769675,10.521260261535645,18.277839715685364,1744060578.7769685,10.521260261535645,2.6320089184567022e-20,1744060578.7769694,10.521260261535645,10,1744060578.7769704,10.521260261535645,0.0,1744060578.7769716,10.521260261535645,-22627416989.969524,1744060578.7769725,10.521260261535645,0.0,1744060578.7769735,10.521260261535645,28284271247.461903
+1744060578.7969856,10.541278839111328,-4.4691444582273405,1744060578.7969873,10.541278839111328,-18.277839715685364,1744060578.7969897,10.541278839111328,0.0,1744060578.7969918,10.541278839111328,56568542496.923805,1744060578.7969928,10.541278839111328,0.0,1744060578.7969944,10.541278839111328,3.231096101730973e-10,1744060578.7969956,10.541278839111328,18.277839715685364,1744060578.7969968,10.541278839111328,2.6320089184567022e-20,1744060578.7969978,10.541278839111328,10,1744060578.796999,10.541278839111328,0.0,1744060578.797,10.541278839111328,-22627416989.969524,1744060578.797001,10.541278839111328,0.0,1744060578.797002,10.541278839111328,28284271247.461903
+1744060578.8169615,10.561258316040039,-4.4691444582273405,1744060578.8169637,10.561258316040039,-18.277839715685364,1744060578.8169656,10.561258316040039,0.0,1744060578.8169675,10.561258316040039,56568542496.923805,1744060578.8169684,10.561258316040039,0.0,1744060578.8169696,10.561258316040039,3.231096101730973e-10,1744060578.816971,10.561258316040039,18.277839715685364,1744060578.816972,10.561258316040039,2.6320089184567022e-20,1744060578.8169732,10.561258316040039,10,1744060578.8169744,10.561258316040039,0.0,1744060578.816975,10.561258316040039,-22627416989.969524,1744060578.816976,10.561258316040039,0.0,1744060578.8169773,10.561258316040039,28284271247.461903
+1744060578.8369064,10.581257343292236,-4.4691444582273405,1744060578.8369083,10.581257343292236,-18.277839715685364,1744060578.8369105,10.581257343292236,0.0,1744060578.8369126,10.581257343292236,56568542496.923805,1744060578.8369136,10.581257343292236,0.0,1744060578.836915,10.581257343292236,3.231096101730973e-10,1744060578.8369164,10.581257343292236,18.277839715685364,1744060578.8369174,10.581257343292236,2.6320089184567022e-20,1744060578.8369188,10.581257343292236,10,1744060578.8369195,10.581257343292236,0.0,1744060578.8369205,10.581257343292236,-22627416989.969524,1744060578.8369217,10.581257343292236,0.0,1744060578.8369226,10.581257343292236,28284271247.461903
+1744060578.8573735,10.60127305984497,-4.4691444582273405,1744060578.8573754,10.60127305984497,-18.277839715685364,1744060578.8573775,10.60127305984497,0.0,1744060578.8573797,10.60127305984497,56568542496.923805,1744060578.8573806,10.60127305984497,0.0,1744060578.8573816,10.60127305984497,3.231096101730973e-10,1744060578.857383,10.60127305984497,18.277839715685364,1744060578.8573842,10.60127305984497,2.6320089184567022e-20,1744060578.8573854,10.60127305984497,10,1744060578.8573864,10.60127305984497,0.0,1744060578.8573873,10.60127305984497,-22627416989.969524,1744060578.8573883,10.60127305984497,0.0,1744060578.8573892,10.60127305984497,28284271247.461903
+1744060578.8769944,10.621229648590088,-4.4691444582273405,1744060578.8769977,10.621229648590088,-18.277839715685364,1744060578.8770013,10.621229648590088,0.0,1744060578.8770044,10.621229648590088,56568542496.923805,1744060578.8770058,10.621229648590088,0.0,1744060578.877008,10.621229648590088,3.231096101730973e-10,1744060578.8770099,10.621229648590088,18.277839715685364,1744060578.8770115,10.621229648590088,2.6320089184567022e-20,1744060578.877013,10.621229648590088,10,1744060578.8770149,10.621229648590088,0.0,1744060578.877017,10.621229648590088,-22627416989.969524,1744060578.8770187,10.621229648590088,0.0,1744060578.8770201,10.621229648590088,28284271247.461903
+1744060578.897557,10.641295909881592,-4.4691444582273405,1744060578.8975594,10.641295909881592,-18.277839715685364,1744060578.8975627,10.641295909881592,0.0,1744060578.8975656,10.641295909881592,56568542496.923805,1744060578.8975677,10.641295909881592,0.0,1744060578.897569,10.641295909881592,3.231096101730973e-10,1744060578.8975708,10.641295909881592,18.277839715685364,1744060578.897572,10.641295909881592,2.6320089184567022e-20,1744060578.897574,10.641295909881592,10,1744060578.8975751,10.641295909881592,0.0,1744060578.8975763,10.641295909881592,-22627416989.969524,1744060578.897578,10.641295909881592,0.0,1744060578.8975792,10.641295909881592,28284271247.461903
+1744060578.9169376,10.66123652458191,-4.4691444582273405,1744060578.9169393,10.66123652458191,-18.277839715685364,1744060578.9169414,10.66123652458191,0.0,1744060578.9169436,10.66123652458191,56568542496.923805,1744060578.9169447,10.66123652458191,0.0,1744060578.916946,10.66123652458191,3.231096101730973e-10,1744060578.916947,10.66123652458191,18.277839715685364,1744060578.9169483,10.66123652458191,2.6320089184567022e-20,1744060578.9169493,10.66123652458191,10,1744060578.9169502,10.66123652458191,0.0,1744060578.9169512,10.66123652458191,-22627416989.969524,1744060578.9169524,10.66123652458191,0.0,1744060578.916953,10.66123652458191,28284271247.461903
+1744060578.936913,10.681224346160889,-4.4691444582273405,1744060578.9369147,10.681224346160889,-18.277839715685364,1744060578.936917,10.681224346160889,0.0,1744060578.9369192,10.681224346160889,56568542496.923805,1744060578.9369206,10.681224346160889,0.0,1744060578.9369218,10.681224346160889,3.231096101730973e-10,1744060578.9369235,10.681224346160889,18.277839715685364,1744060578.9369247,10.681224346160889,2.6320089184567022e-20,1744060578.9369256,10.681224346160889,10,1744060578.9369266,10.681224346160889,0.0,1744060578.9369278,10.681224346160889,-22627416989.969524,1744060578.9369287,10.681224346160889,0.0,1744060578.9369297,10.681224346160889,28284271247.461903
+1744060578.9574544,10.701276540756226,-4.4691444582273405,1744060578.957456,10.701276540756226,-18.277839715685364,1744060578.9574583,10.701276540756226,0.0,1744060578.95746,10.701276540756226,56568542496.923805,1744060578.9574609,10.701276540756226,0.0,1744060578.9574623,10.701276540756226,3.231096101730973e-10,1744060578.9574633,10.701276540756226,18.277839715685364,1744060578.9574647,10.701276540756226,2.6320089184567022e-20,1744060578.9574656,10.701276540756226,10,1744060578.9574666,10.701276540756226,0.0,1744060578.9574673,10.701276540756226,-22627416989.969524,1744060578.9574685,10.701276540756226,0.0,1744060578.9574695,10.701276540756226,28284271247.461903
+1744060578.9769595,10.721258640289307,-4.4691444582273405,1744060578.9769614,10.721258640289307,-18.277839715685364,1744060578.9769635,10.721258640289307,0.0,1744060578.9769657,10.721258640289307,56568542496.923805,1744060578.9769666,10.721258640289307,0.0,1744060578.976968,10.721258640289307,3.231096101730973e-10,1744060578.9769695,10.721258640289307,18.277839715685364,1744060578.9769707,10.721258640289307,2.6320089184567022e-20,1744060578.9769719,10.721258640289307,10,1744060578.9769728,10.721258640289307,0.0,1744060578.9769735,10.721258640289307,-22627416989.969524,1744060578.976975,10.721258640289307,0.0,1744060578.976976,10.721258640289307,28284271247.461903
+1744060578.9970348,10.74124813079834,-4.4691444582273405,1744060578.9970365,10.74124813079834,-18.277839715685364,1744060578.9970388,10.74124813079834,0.0,1744060578.9970415,10.74124813079834,56568542496.923805,1744060578.9970424,10.74124813079834,0.0,1744060578.9970436,10.74124813079834,3.231096101730973e-10,1744060578.997045,10.74124813079834,18.277839715685364,1744060578.997046,10.74124813079834,2.6320089184567022e-20,1744060578.9970472,10.74124813079834,10,1744060578.9970484,10.74124813079834,0.0,1744060578.9970493,10.74124813079834,-22627416989.969524,1744060578.9970503,10.74124813079834,0.0,1744060578.9970515,10.74124813079834,28284271247.461903
+1744060579.0169997,10.761250972747803,-4.4691444582273405,1744060579.0170016,10.761250972747803,-18.277839715685364,1744060579.017004,10.761250972747803,0.0,1744060579.0170064,10.761250972747803,56568542496.923805,1744060579.0170076,10.761250972747803,0.0,1744060579.0170088,10.761250972747803,3.231096101730973e-10,1744060579.0170102,10.761250972747803,18.277839715685364,1744060579.0170112,10.761250972747803,2.6320089184567022e-20,1744060579.0170126,10.761250972747803,10,1744060579.0170135,10.761250972747803,0.0,1744060579.0170145,10.761250972747803,-22627416989.969524,1744060579.0170155,10.761250972747803,0.0,1744060579.0170166,10.761250972747803,28284271247.461903
+1744060579.0370426,10.781256198883057,-4.4691444582273405,1744060579.0370445,10.781256198883057,-18.277839715685364,1744060579.0370464,10.781256198883057,0.0,1744060579.0370488,10.781256198883057,56568542496.923805,1744060579.0370498,10.781256198883057,0.0,1744060579.0370512,10.781256198883057,3.231096101730973e-10,1744060579.0370522,10.781256198883057,18.277839715685364,1744060579.0370533,10.781256198883057,2.6320089184567022e-20,1744060579.0370545,10.781256198883057,10,1744060579.0370557,10.781256198883057,0.0,1744060579.0370564,10.781256198883057,-22627416989.969524,1744060579.0370576,10.781256198883057,0.0,1744060579.0370586,10.781256198883057,28284271247.461903
+1744060579.057412,10.80126428604126,-4.4691444582273405,1744060579.0574138,10.80126428604126,-18.277839715685364,1744060579.057416,10.80126428604126,0.0,1744060579.0574179,10.80126428604126,56568542496.923805,1744060579.057419,10.80126428604126,0.0,1744060579.0574205,10.80126428604126,3.231096101730973e-10,1744060579.0574217,10.80126428604126,18.277839715685364,1744060579.0574226,10.80126428604126,2.6320089184567022e-20,1744060579.0574238,10.80126428604126,10,1744060579.0574248,10.80126428604126,0.0,1744060579.057426,10.80126428604126,-22627416989.969524,1744060579.057427,10.80126428604126,0.0,1744060579.0574276,10.80126428604126,28284271247.461903
+1744060579.077126,10.821314334869385,-4.4691444582273405,1744060579.0771277,10.821314334869385,-18.277839715685364,1744060579.07713,10.821314334869385,0.0,1744060579.0771322,10.821314334869385,56568542496.923805,1744060579.0771334,10.821314334869385,0.0,1744060579.0771344,10.821314334869385,3.231096101730973e-10,1744060579.0771358,10.821314334869385,18.277839715685364,1744060579.077137,10.821314334869385,2.6320089184567022e-20,1744060579.0771382,10.821314334869385,10,1744060579.077139,10.821314334869385,0.0,1744060579.0771396,10.821314334869385,-22627416989.969524,1744060579.0771408,10.821314334869385,0.0,1744060579.0771418,10.821314334869385,28284271247.461903
+1744060579.097034,10.841229438781738,-4.4691444582273405,1744060579.097036,10.841229438781738,-18.277839715685364,1744060579.097038,10.841229438781738,0.0,1744060579.0970402,10.841229438781738,56568542496.923805,1744060579.0970414,10.841229438781738,0.0,1744060579.0970428,10.841229438781738,3.231096101730973e-10,1744060579.0970438,10.841229438781738,18.277839715685364,1744060579.097045,10.841229438781738,2.6320089184567022e-20,1744060579.097046,10.841229438781738,10,1744060579.097047,10.841229438781738,0.0,1744060579.097048,10.841229438781738,-22627416989.969524,1744060579.097049,10.841229438781738,0.0,1744060579.0970502,10.841229438781738,28284271247.461903
+1744060579.1173751,10.861260890960693,-4.4691444582273405,1744060579.1173778,10.861260890960693,-18.277839715685364,1744060579.1173804,10.861260890960693,0.0,1744060579.1173823,10.861260890960693,56568542496.923805,1744060579.1173837,10.861260890960693,0.0,1744060579.1173851,10.861260890960693,3.231096101730973e-10,1744060579.1173866,10.861260890960693,18.277839715685364,1744060579.117388,10.861260890960693,2.6320089184567022e-20,1744060579.1173892,10.861260890960693,10,1744060579.1173904,10.861260890960693,0.0,1744060579.1173913,10.861260890960693,-22627416989.969524,1744060579.1173923,10.861260890960693,0.0,1744060579.1173935,10.861260890960693,28284271247.461903
+1744060579.1376202,10.881294250488281,-4.4691444582273405,1744060579.137622,10.881294250488281,-18.277839715685364,1744060579.1376243,10.881294250488281,0.0,1744060579.1376264,10.881294250488281,56568542496.923805,1744060579.1376276,10.881294250488281,0.0,1744060579.1376286,10.881294250488281,3.231096101730973e-10,1744060579.13763,10.881294250488281,18.277839715685364,1744060579.137631,10.881294250488281,2.6320089184567022e-20,1744060579.137632,10.881294250488281,10,1744060579.137633,10.881294250488281,0.0,1744060579.137634,10.881294250488281,-22627416989.969524,1744060579.137635,10.881294250488281,0.0,1744060579.1376362,10.881294250488281,28284271247.461903
+1744060579.157346,10.901280403137207,-4.4691444582273405,1744060579.157348,10.901280403137207,-18.277839715685364,1744060579.1573498,10.901280403137207,0.0,1744060579.1573522,10.901280403137207,56568542496.923805,1744060579.1573532,10.901280403137207,0.0,1744060579.1573546,10.901280403137207,3.231096101730973e-10,1744060579.1573558,10.901280403137207,18.277839715685364,1744060579.1573572,10.901280403137207,2.6320089184567022e-20,1744060579.1573586,10.901280403137207,10,1744060579.1573596,10.901280403137207,0.0,1744060579.1573606,10.901280403137207,-22627416989.969524,1744060579.1573617,10.901280403137207,0.0,1744060579.1573627,10.901280403137207,28284271247.461903
+1744060579.1770043,10.921298503875732,-4.4691444582273405,1744060579.177006,10.921298503875732,-18.277839715685364,1744060579.1770084,10.921298503875732,0.0,1744060579.177011,10.921298503875732,56568542496.923805,1744060579.177012,10.921298503875732,0.0,1744060579.1770132,10.921298503875732,3.231096101730973e-10,1744060579.1770144,10.921298503875732,18.277839715685364,1744060579.1770153,10.921298503875732,2.6320089184567022e-20,1744060579.1770165,10.921298503875732,10,1744060579.1770177,10.921298503875732,0.0,1744060579.1770184,10.921298503875732,-22627416989.969524,1744060579.1770194,10.921298503875732,0.0,1744060579.1770203,10.921298503875732,28284271247.461903
+1744060579.1969564,10.941256523132324,-4.4691444582273405,1744060579.1969583,10.941256523132324,-18.277839715685364,1744060579.1969602,10.941256523132324,0.0,1744060579.1969628,10.941256523132324,56568542496.923805,1744060579.1969638,10.941256523132324,0.0,1744060579.1969652,10.941256523132324,3.231096101730973e-10,1744060579.1969662,10.941256523132324,18.277839715685364,1744060579.1969671,10.941256523132324,2.6320089184567022e-20,1744060579.1969686,10.941256523132324,10,1744060579.1969695,10.941256523132324,0.0,1744060579.1969702,10.941256523132324,-22627416989.969524,1744060579.1969712,10.941256523132324,0.0,1744060579.1969724,10.941256523132324,28284271247.461903
+1744060579.216971,10.961272954940796,-4.4691444582273405,1744060579.2169728,10.961272954940796,-18.277839715685364,1744060579.2169747,10.961272954940796,0.0,1744060579.2169771,10.961272954940796,56568542496.923805,1744060579.216978,10.961272954940796,0.0,1744060579.2169795,10.961272954940796,3.231096101730973e-10,1744060579.2169805,10.961272954940796,18.277839715685364,1744060579.2169814,10.961272954940796,2.6320089184567022e-20,1744060579.2169828,10.961272954940796,10,1744060579.2169838,10.961272954940796,0.0,1744060579.2169847,10.961272954940796,-22627416989.969524,1744060579.216986,10.961272954940796,0.0,1744060579.2169867,10.961272954940796,28284271247.461903
+1744060579.236997,10.9812593460083,-4.4691444582273405,1744060579.2369988,10.9812593460083,-18.277839715685364,1744060579.237001,10.9812593460083,0.0,1744060579.2370033,10.9812593460083,56568542496.923805,1744060579.2370043,10.9812593460083,0.0,1744060579.2370055,10.9812593460083,3.231096101730973e-10,1744060579.2370067,10.9812593460083,18.277839715685364,1744060579.2370079,10.9812593460083,2.6320089184567022e-20,1744060579.237009,10.9812593460083,10,1744060579.2370102,10.9812593460083,0.0,1744060579.237011,10.9812593460083,-22627416989.969524,1744060579.237012,10.9812593460083,0.0,1744060579.237013,10.9812593460083,28284271247.461903
+1744060579.2573118,11.001238346099854,-5.13735516063899,1744060579.2573135,11.001238346099854,-21.32213178286257,1744060579.2573156,11.001238346099854,0.0,1744060579.2573175,11.001238346099854,56568542496.923805,1744060579.2573187,11.001238346099854,0.0,1744060579.2573197,11.001238346099854,3.7692559927782594e-10,1744060579.257321,11.001238346099854,21.32213178286257,1744060579.257322,11.001238346099854,3.070386975957417e-20,1744060579.257323,11.001238346099854,10,1744060579.257324,11.001238346099854,0.0,1744060579.2573252,11.001238346099854,-22627416989.969524,1744060579.2573261,11.001238346099854,0.0,1744060579.2573268,11.001238346099854,28284271247.461903
+1744060579.2770102,11.021263122558594,-5.13735516063899,1744060579.2770119,11.021263122558594,-21.32213178286257,1744060579.2770143,11.021263122558594,0.0,1744060579.2770166,11.021263122558594,56568542496.923805,1744060579.2770176,11.021263122558594,0.0,1744060579.2770188,11.021263122558594,3.7692559927782594e-10,1744060579.2770202,11.021263122558594,21.32213178286257,1744060579.2770212,11.021263122558594,3.070386975957417e-20,1744060579.2770224,11.021263122558594,10,1744060579.2770236,11.021263122558594,0.0,1744060579.2770243,11.021263122558594,-22627416989.969524,1744060579.2770255,11.021263122558594,0.0,1744060579.2770267,11.021263122558594,28284271247.461903
+1744060579.2969544,11.041249990463257,-5.13735516063899,1744060579.296956,11.041249990463257,-21.32213178286257,1744060579.2969584,11.041249990463257,0.0,1744060579.2969608,11.041249990463257,56568542496.923805,1744060579.296962,11.041249990463257,0.0,1744060579.296963,11.041249990463257,3.7692559927782594e-10,1744060579.2969642,11.041249990463257,21.32213178286257,1744060579.2969654,11.041249990463257,3.070386975957417e-20,1744060579.2969663,11.041249990463257,10,1744060579.2969675,11.041249990463257,0.0,1744060579.2969685,11.041249990463257,-22627416989.969524,1744060579.2969694,11.041249990463257,0.0,1744060579.2969708,11.041249990463257,28284271247.461903
+1744060579.3169136,11.061251401901245,-5.13735516063899,1744060579.3169155,11.061251401901245,-21.32213178286257,1744060579.3169177,11.061251401901245,0.0,1744060579.3169198,11.061251401901245,56568542496.923805,1744060579.3169208,11.061251401901245,0.0,1744060579.3169222,11.061251401901245,3.7692559927782594e-10,1744060579.3169234,11.061251401901245,21.32213178286257,1744060579.3169243,11.061251401901245,3.070386975957417e-20,1744060579.3169255,11.061251401901245,10,1744060579.3169265,11.061251401901245,0.0,1744060579.3169274,11.061251401901245,-22627416989.969524,1744060579.3169286,11.061251401901245,0.0,1744060579.3169293,11.061251401901245,28284271247.461903
+1744060579.336943,11.081254482269287,-5.13735516063899,1744060579.3369446,11.081254482269287,-21.32213178286257,1744060579.3369467,11.081254482269287,0.0,1744060579.336949,11.081254482269287,56568542496.923805,1744060579.33695,11.081254482269287,0.0,1744060579.3369513,11.081254482269287,3.7692559927782594e-10,1744060579.3369527,11.081254482269287,21.32213178286257,1744060579.3369536,11.081254482269287,3.070386975957417e-20,1744060579.336955,11.081254482269287,10,1744060579.3369558,11.081254482269287,0.0,1744060579.336957,11.081254482269287,-22627416989.969524,1744060579.336958,11.081254482269287,0.0,1744060579.336959,11.081254482269287,28284271247.461903
+1744060579.3572516,11.101257085800171,-5.13735516063899,1744060579.3572533,11.101257085800171,-21.32213178286257,1744060579.3572555,11.101257085800171,0.0,1744060579.3572574,11.101257085800171,56568542496.923805,1744060579.3572586,11.101257085800171,0.0,1744060579.3572598,11.101257085800171,3.7692559927782594e-10,1744060579.3572607,11.101257085800171,21.32213178286257,1744060579.357262,11.101257085800171,3.070386975957417e-20,1744060579.3572628,11.101257085800171,10,1744060579.3572638,11.101257085800171,0.0,1744060579.357265,11.101257085800171,-22627416989.969524,1744060579.357266,11.101257085800171,0.0,1744060579.3572667,11.101257085800171,28284271247.461903
+1744060579.377048,11.121275186538696,-5.13735516063899,1744060579.37705,11.121275186538696,-21.32213178286257,1744060579.3770518,11.121275186538696,0.0,1744060579.3770542,11.121275186538696,56568542496.923805,1744060579.3770552,11.121275186538696,0.0,1744060579.3770564,11.121275186538696,3.7692559927782594e-10,1744060579.3770576,11.121275186538696,21.32213178286257,1744060579.3770587,11.121275186538696,3.070386975957417e-20,1744060579.37706,11.121275186538696,10,1744060579.377061,11.121275186538696,0.0,1744060579.3770618,11.121275186538696,-22627416989.969524,1744060579.3770628,11.121275186538696,0.0,1744060579.377064,11.121275186538696,28284271247.461903
+1744060579.3970234,11.14126181602478,-5.13735516063899,1744060579.3970253,11.14126181602478,-21.32213178286257,1744060579.3970277,11.14126181602478,0.0,1744060579.39703,11.14126181602478,56568542496.923805,1744060579.397031,11.14126181602478,0.0,1744060579.3970325,11.14126181602478,3.7692559927782594e-10,1744060579.3970337,11.14126181602478,21.32213178286257,1744060579.3970346,11.14126181602478,3.070386975957417e-20,1744060579.3970358,11.14126181602478,10,1744060579.3970368,11.14126181602478,0.0,1744060579.3970377,11.14126181602478,-22627416989.969524,1744060579.3970392,11.14126181602478,0.0,1744060579.3970401,11.14126181602478,28284271247.461903
+1744060579.416888,11.161243677139282,-5.13735516063899,1744060579.41689,11.161243677139282,-21.32213178286257,1744060579.4168918,11.161243677139282,0.0,1744060579.416894,11.161243677139282,56568542496.923805,1744060579.416895,11.161243677139282,0.0,1744060579.4168963,11.161243677139282,3.7692559927782594e-10,1744060579.4168975,11.161243677139282,21.32213178286257,1744060579.4168985,11.161243677139282,3.070386975957417e-20,1744060579.4168997,11.161243677139282,10,1744060579.4169006,11.161243677139282,0.0,1744060579.4169016,11.161243677139282,-22627416989.969524,1744060579.4169025,11.161243677139282,0.0,1744060579.4169037,11.161243677139282,28284271247.461903
+1744060579.436925,11.181248664855957,-5.13735516063899,1744060579.436927,11.181248664855957,-21.32213178286257,1744060579.436929,11.181248664855957,0.0,1744060579.4369311,11.181248664855957,56568542496.923805,1744060579.436932,11.181248664855957,0.0,1744060579.4369333,11.181248664855957,3.7692559927782594e-10,1744060579.4369345,11.181248664855957,21.32213178286257,1744060579.4369357,11.181248664855957,3.070386975957417e-20,1744060579.4369366,11.181248664855957,10,1744060579.4369378,11.181248664855957,0.0,1744060579.4369388,11.181248664855957,-22627416989.969524,1744060579.4369397,11.181248664855957,0.0,1744060579.436941,11.181248664855957,28284271247.461903
+1744060579.4578404,11.201228380203247,-5.13735516063899,1744060579.4578426,11.201228380203247,-21.32213178286257,1744060579.4578452,11.201228380203247,0.0,1744060579.4578474,11.201228380203247,56568542496.923805,1744060579.4578488,11.201228380203247,0.0,1744060579.4578502,11.201228380203247,3.7692559927782594e-10,1744060579.4578516,11.201228380203247,21.32213178286257,1744060579.4578526,11.201228380203247,3.070386975957417e-20,1744060579.457854,11.201228380203247,10,1744060579.457855,11.201228380203247,0.0,1744060579.457856,11.201228380203247,-22627416989.969524,1744060579.4578571,11.201228380203247,0.0,1744060579.4578578,11.201228380203247,28284271247.461903
+1744060579.476901,11.221250534057617,-5.13735516063899,1744060579.476903,11.221250534057617,-21.32213178286257,1744060579.4769049,11.221250534057617,0.0,1744060579.476907,11.221250534057617,56568542496.923805,1744060579.476908,11.221250534057617,0.0,1744060579.4769094,11.221250534057617,3.7692559927782594e-10,1744060579.4769104,11.221250534057617,21.32213178286257,1744060579.4769113,11.221250534057617,3.070386975957417e-20,1744060579.4769127,11.221250534057617,10,1744060579.4769135,11.221250534057617,0.0,1744060579.4769144,11.221250534057617,-22627416989.969524,1744060579.4769154,11.221250534057617,0.0,1744060579.4769166,11.221250534057617,28284271247.461903
+1744060579.4971697,11.241229772567749,-5.13735516063899,1744060579.4971726,11.241229772567749,-21.32213178286257,1744060579.497175,11.241229772567749,0.0,1744060579.4971771,11.241229772567749,56568542496.923805,1744060579.4971786,11.241229772567749,0.0,1744060579.4971802,11.241229772567749,3.7692559927782594e-10,1744060579.4971812,11.241229772567749,21.32213178286257,1744060579.497183,11.241229772567749,3.070386975957417e-20,1744060579.497184,11.241229772567749,10,1744060579.4971855,11.241229772567749,0.0,1744060579.4971867,11.241229772567749,-22627416989.969524,1744060579.4971879,11.241229772567749,0.0,1744060579.4971888,11.241229772567749,28284271247.461903
+1744060579.516935,11.261232376098633,-5.13735516063899,1744060579.5169373,11.261232376098633,-21.32213178286257,1744060579.5169392,11.261232376098633,0.0,1744060579.5169413,11.261232376098633,56568542496.923805,1744060579.5169423,11.261232376098633,0.0,1744060579.5169437,11.261232376098633,3.7692559927782594e-10,1744060579.5169446,11.261232376098633,21.32213178286257,1744060579.5169456,11.261232376098633,3.070386975957417e-20,1744060579.516947,11.261232376098633,10,1744060579.516948,11.261232376098633,0.0,1744060579.5169487,11.261232376098633,-22627416989.969524,1744060579.5169497,11.261232376098633,0.0,1744060579.5169508,11.261232376098633,28284271247.461903
+1744060579.5369067,11.281242609024048,-5.13735516063899,1744060579.5369086,11.281242609024048,-21.32213178286257,1744060579.5369105,11.281242609024048,0.0,1744060579.536913,11.281242609024048,56568542496.923805,1744060579.5369139,11.281242609024048,0.0,1744060579.5369153,11.281242609024048,3.7692559927782594e-10,1744060579.5369163,11.281242609024048,21.32213178286257,1744060579.5369172,11.281242609024048,3.070386975957417e-20,1744060579.5369186,11.281242609024048,10,1744060579.5369196,11.281242609024048,0.0,1744060579.5369203,11.281242609024048,-22627416989.969524,1744060579.5369213,11.281242609024048,0.0,1744060579.5369225,11.281242609024048,28284271247.461903
+1744060579.5572355,11.301260948181152,-5.13735516063899,1744060579.5572374,11.301260948181152,-21.32213178286257,1744060579.5572393,11.301260948181152,0.0,1744060579.5572417,11.301260948181152,56568542496.923805,1744060579.5572426,11.301260948181152,0.0,1744060579.5572438,11.301260948181152,3.7692559927782594e-10,1744060579.557245,11.301260948181152,21.32213178286257,1744060579.557246,11.301260948181152,3.070386975957417e-20,1744060579.5572472,11.301260948181152,10,1744060579.5572484,11.301260948181152,0.0,1744060579.5572493,11.301260948181152,-22627416989.969524,1744060579.5572503,11.301260948181152,0.0,1744060579.5572512,11.301260948181152,28284271247.461903
+1744060579.5768921,11.321248769760132,-5.13735516063899,1744060579.576894,11.321248769760132,-21.32213178286257,1744060579.576896,11.321248769760132,0.0,1744060579.576898,11.321248769760132,56568542496.923805,1744060579.5768993,11.321248769760132,0.0,1744060579.5769002,11.321248769760132,3.7692559927782594e-10,1744060579.5769017,11.321248769760132,21.32213178286257,1744060579.5769029,11.321248769760132,3.070386975957417e-20,1744060579.5769038,11.321248769760132,10,1744060579.576905,11.321248769760132,0.0,1744060579.5769057,11.321248769760132,-22627416989.969524,1744060579.5769067,11.321248769760132,0.0,1744060579.5769079,11.321248769760132,28284271247.461903
+1744060579.5974212,11.341338634490967,-5.13735516063899,1744060579.597424,11.341338634490967,-21.32213178286257,1744060579.5974271,11.341338634490967,0.0,1744060579.5974305,11.341338634490967,56568542496.923805,1744060579.5974324,11.341338634490967,0.0,1744060579.5974345,11.341338634490967,3.7692559927782594e-10,1744060579.5974367,11.341338634490967,21.32213178286257,1744060579.5974386,11.341338634490967,3.070386975957417e-20,1744060579.5974405,11.341338634490967,10,1744060579.5974422,11.341338634490967,0.0,1744060579.597443,11.341338634490967,-22627416989.969524,1744060579.597444,11.341338634490967,0.0,1744060579.5974455,11.341338634490967,28284271247.461903
+1744060579.616989,11.361268520355225,-5.13735516063899,1744060579.6169908,11.361268520355225,-21.32213178286257,1744060579.6169927,11.361268520355225,0.0,1744060579.616995,11.361268520355225,56568542496.923805,1744060579.616996,11.361268520355225,0.0,1744060579.6169975,11.361268520355225,3.7692559927782594e-10,1744060579.6169987,11.361268520355225,21.32213178286257,1744060579.6169996,11.361268520355225,3.070386975957417e-20,1744060579.6170008,11.361268520355225,10,1744060579.6170018,11.361268520355225,0.0,1744060579.6170027,11.361268520355225,-22627416989.969524,1744060579.617004,11.361268520355225,0.0,1744060579.617005,11.361268520355225,28284271247.461903
+1744060579.6368937,11.38122296333313,-5.13735516063899,1744060579.6368957,11.38122296333313,-21.32213178286257,1744060579.636898,11.38122296333313,0.0,1744060579.6369002,11.38122296333313,56568542496.923805,1744060579.6369014,11.38122296333313,0.0,1744060579.6369026,11.38122296333313,3.7692559927782594e-10,1744060579.6369038,11.38122296333313,21.32213178286257,1744060579.636905,11.38122296333313,3.070386975957417e-20,1744060579.636906,11.38122296333313,10,1744060579.636907,11.38122296333313,0.0,1744060579.636908,11.38122296333313,-22627416989.969524,1744060579.6369088,11.38122296333313,0.0,1744060579.6369097,11.38122296333313,28284271247.461903
+1744060579.657917,11.401257038116455,-5.13735516063899,1744060579.6579204,11.401257038116455,-21.32213178286257,1744060579.6579242,11.401257038116455,0.0,1744060579.657928,11.401257038116455,56568542496.923805,1744060579.65793,11.401257038116455,0.0,1744060579.6579325,11.401257038116455,3.7692559927782594e-10,1744060579.6579351,11.401257038116455,21.32213178286257,1744060579.6579375,11.401257038116455,3.070386975957417e-20,1744060579.6579397,11.401257038116455,10,1744060579.6579418,11.401257038116455,0.0,1744060579.6579437,11.401257038116455,-22627416989.969524,1744060579.6579459,11.401257038116455,0.0,1744060579.657948,11.401257038116455,28284271247.461903
+1744060579.6772506,11.421261310577393,-5.13735516063899,1744060579.6772525,11.421261310577393,-21.32213178286257,1744060579.6772559,11.421261310577393,0.0,1744060579.6772592,11.421261310577393,56568542496.923805,1744060579.6772614,11.421261310577393,0.0,1744060579.677264,11.421261310577393,3.7692559927782594e-10,1744060579.6772661,11.421261310577393,21.32213178286257,1744060579.677268,11.421261310577393,3.070386975957417e-20,1744060579.6772702,11.421261310577393,10,1744060579.6772726,11.421261310577393,0.0,1744060579.677275,11.421261310577393,-22627416989.969524,1744060579.6772768,11.421261310577393,0.0,1744060579.677279,11.421261310577393,28284271247.461903
+1744060579.697506,11.441309928894043,-5.13735516063899,1744060579.6975086,11.441309928894043,-21.32213178286257,1744060579.6975112,11.441309928894043,0.0,1744060579.6975138,11.441309928894043,56568542496.923805,1744060579.6975152,11.441309928894043,0.0,1744060579.6975164,11.441309928894043,3.7692559927782594e-10,1744060579.697518,11.441309928894043,21.32213178286257,1744060579.6975193,11.441309928894043,3.070386975957417e-20,1744060579.6975207,11.441309928894043,10,1744060579.6975217,11.441309928894043,0.0,1744060579.6975224,11.441309928894043,-22627416989.969524,1744060579.6975236,11.441309928894043,0.0,1744060579.6975248,11.441309928894043,28284271247.461903
+1744060579.7169702,11.461257219314575,-5.13735516063899,1744060579.716972,11.461257219314575,-21.32213178286257,1744060579.716974,11.461257219314575,0.0,1744060579.7169766,11.461257219314575,56568542496.923805,1744060579.7169776,11.461257219314575,0.0,1744060579.716979,11.461257219314575,3.7692559927782594e-10,1744060579.71698,11.461257219314575,21.32213178286257,1744060579.7169812,11.461257219314575,3.070386975957417e-20,1744060579.7169826,11.461257219314575,10,1744060579.7169836,11.461257219314575,0.0,1744060579.7169843,11.461257219314575,-22627416989.969524,1744060579.7169852,11.461257219314575,0.0,1744060579.7169864,11.461257219314575,28284271247.461903
+1744060579.7369792,11.481248617172241,-5.13735516063899,1744060579.736981,11.481248617172241,-21.32213178286257,1744060579.7369833,11.481248617172241,0.0,1744060579.736986,11.481248617172241,56568542496.923805,1744060579.7369869,11.481248617172241,0.0,1744060579.736988,11.481248617172241,3.7692559927782594e-10,1744060579.7369895,11.481248617172241,21.32213178286257,1744060579.7369907,11.481248617172241,3.070386975957417e-20,1744060579.736992,11.481248617172241,10,1744060579.7369928,11.481248617172241,0.0,1744060579.7369938,11.481248617172241,-22627416989.969524,1744060579.7369947,11.481248617172241,0.0,1744060579.736996,11.481248617172241,28284271247.461903
+1744060579.7577386,11.50127387046814,-5.712634523648786,1744060579.7577424,11.50127387046814,-23.9930596991462,1744060579.7577448,11.50127387046814,0.0,1744060579.7577477,11.50127387046814,56568542496.923805,1744060579.7577496,11.50127387046814,0.0,1744060579.7577512,11.50127387046814,4.241413803091706e-10,1744060579.7577531,11.50127387046814,23.9930596991462,1744060579.7577546,11.50127387046814,3.455000595734934e-20,1744060579.7577565,11.50127387046814,10,1744060579.757758,11.50127387046814,0.0,1744060579.7577593,11.50127387046814,-22627416989.969524,1744060579.7577605,11.50127387046814,0.0,1744060579.7577622,11.50127387046814,28284271247.461903
+1744060579.7775807,11.521268606185913,-5.712634523648786,1744060579.7775838,11.521268606185913,-23.9930596991462,1744060579.777587,11.521268606185913,0.0,1744060579.77759,11.521268606185913,56568542496.923805,1744060579.7775915,11.521268606185913,0.0,1744060579.7775936,11.521268606185913,4.241413803091706e-10,1744060579.777596,11.521268606185913,23.9930596991462,1744060579.7775977,11.521268606185913,3.455000595734934e-20,1744060579.7775996,11.521268606185913,10,1744060579.7776012,11.521268606185913,0.0,1744060579.7776027,11.521268606185913,-22627416989.969524,1744060579.777604,11.521268606185913,0.0,1744060579.7776055,11.521268606185913,28284271247.461903
+1744060579.7972033,11.54124641418457,-5.712634523648786,1744060579.7972054,11.54124641418457,-23.9930596991462,1744060579.7972083,11.54124641418457,0.0,1744060579.7972124,11.54124641418457,56568542496.923805,1744060579.797214,11.54124641418457,0.0,1744060579.7972157,11.54124641418457,4.241413803091706e-10,1744060579.7972171,11.54124641418457,23.9930596991462,1744060579.797218,11.54124641418457,3.455000595734934e-20,1744060579.7972193,11.54124641418457,10,1744060579.7972205,11.54124641418457,0.0,1744060579.7972212,11.54124641418457,-22627416989.969524,1744060579.7972221,11.54124641418457,0.0,1744060579.797223,11.54124641418457,28284271247.461903
+1744060579.8169684,11.561264991760254,-5.712634523648786,1744060579.8169708,11.561264991760254,-23.9930596991462,1744060579.8169727,11.561264991760254,0.0,1744060579.816975,11.561264991760254,56568542496.923805,1744060579.816976,11.561264991760254,0.0,1744060579.8169775,11.561264991760254,4.241413803091706e-10,1744060579.8169785,11.561264991760254,23.9930596991462,1744060579.8169796,11.561264991760254,3.455000595734934e-20,1744060579.8169808,11.561264991760254,10,1744060579.8169818,11.561264991760254,0.0,1744060579.8169825,11.561264991760254,-22627416989.969524,1744060579.8169835,11.561264991760254,0.0,1744060579.8169847,11.561264991760254,28284271247.461903
+1744060579.8372667,11.581252813339233,-5.712634523648786,1744060579.8372686,11.581252813339233,-23.9930596991462,1744060579.8372705,11.581252813339233,0.0,1744060579.8372726,11.581252813339233,56568542496.923805,1744060579.8372736,11.581252813339233,0.0,1744060579.8372748,11.581252813339233,4.241413803091706e-10,1744060579.8372762,11.581252813339233,23.9930596991462,1744060579.8372772,11.581252813339233,3.455000595734934e-20,1744060579.8372781,11.581252813339233,10,1744060579.8372793,11.581252813339233,0.0,1744060579.83728,11.581252813339233,-22627416989.969524,1744060579.837281,11.581252813339233,0.0,1744060579.837282,11.581252813339233,28284271247.461903
+1744060579.8587067,11.601364135742188,-5.712634523648786,1744060579.8587093,11.601364135742188,-23.9930596991462,1744060579.8587112,11.601364135742188,0.0,1744060579.8587139,11.601364135742188,56568542496.923805,1744060579.858715,11.601364135742188,0.0,1744060579.8587165,11.601364135742188,4.241413803091706e-10,1744060579.8587174,11.601364135742188,23.9930596991462,1744060579.8587186,11.601364135742188,3.455000595734934e-20,1744060579.85872,11.601364135742188,10,1744060579.8587208,11.601364135742188,0.0,1744060579.8587217,11.601364135742188,-22627416989.969524,1744060579.8587232,11.601364135742188,0.0,1744060579.858724,11.601364135742188,28284271247.461903
+1744060579.8769453,11.621225833892822,-5.712634523648786,1744060579.876947,11.621225833892822,-23.9930596991462,1744060579.8769493,11.621225833892822,0.0,1744060579.8769515,11.621225833892822,56568542496.923805,1744060579.8769526,11.621225833892822,0.0,1744060579.876976,11.621225833892822,4.241413803091706e-10,1744060579.8769777,11.621225833892822,23.9930596991462,1744060579.8769789,11.621225833892822,3.455000595734934e-20,1744060579.8769803,11.621225833892822,10,1744060579.8769813,11.621225833892822,0.0,1744060579.8769822,11.621225833892822,-22627416989.969524,1744060579.8769834,11.621225833892822,0.0,1744060579.8769848,11.621225833892822,28284271247.461903
+1744060579.896931,11.641227006912231,-5.712634523648786,1744060579.8969326,11.641227006912231,-23.9930596991462,1744060579.8969347,11.641227006912231,0.0,1744060579.896937,11.641227006912231,56568542496.923805,1744060579.896938,11.641227006912231,0.0,1744060579.8969393,11.641227006912231,4.241413803091706e-10,1744060579.8969402,11.641227006912231,23.9930596991462,1744060579.8969417,11.641227006912231,3.455000595734934e-20,1744060579.8969426,11.641227006912231,10,1744060579.8969438,11.641227006912231,0.0,1744060579.8969445,11.641227006912231,-22627416989.969524,1744060579.8969457,11.641227006912231,0.0,1744060579.8969467,11.641227006912231,28284271247.461903
+1744060579.9178867,11.661367177963257,-5.712634523648786,1744060579.9178894,11.661367177963257,-23.9930596991462,1744060579.9178915,11.661367177963257,0.0,1744060579.9178944,11.661367177963257,56568542496.923805,1744060579.9178958,11.661367177963257,0.0,1744060579.9178972,11.661367177963257,4.241413803091706e-10,1744060579.9178984,11.661367177963257,23.9930596991462,1744060579.9179196,11.661367177963257,3.455000595734934e-20,1744060579.9179215,11.661367177963257,10,1744060579.9179225,11.661367177963257,0.0,1744060579.917924,11.661367177963257,-22627416989.969524,1744060579.9179254,11.661367177963257,0.0,1744060579.9179263,11.661367177963257,28284271247.461903
+1744060579.9378178,11.681323766708374,-5.712634523648786,1744060579.9378207,11.681323766708374,-23.9930596991462,1744060579.937823,11.681323766708374,0.0,1744060579.937825,11.681323766708374,56568542496.923805,1744060579.9378262,11.681323766708374,0.0,1744060579.9378273,11.681323766708374,4.241413803091706e-10,1744060579.9378283,11.681323766708374,23.9930596991462,1744060579.9378295,11.681323766708374,3.455000595734934e-20,1744060579.9378307,11.681323766708374,10,1744060579.9378316,11.681323766708374,0.0,1744060579.9378326,11.681323766708374,-22627416989.969524,1744060579.937834,11.681323766708374,0.0,1744060579.937835,11.681323766708374,28284271247.461903
+1744060579.9573557,11.70126724243164,-5.712634523648786,1744060579.9573574,11.70126724243164,-23.9930596991462,1744060579.9573598,11.70126724243164,0.0,1744060579.957362,11.70126724243164,56568542496.923805,1744060579.9573631,11.70126724243164,0.0,1744060579.9573646,11.70126724243164,4.241413803091706e-10,1744060579.9573658,11.70126724243164,23.9930596991462,1744060579.9573667,11.70126724243164,3.455000595734934e-20,1744060579.9573681,11.70126724243164,10,1744060579.957369,11.70126724243164,0.0,1744060579.9573703,11.70126724243164,-22627416989.969524,1744060579.9573712,11.70126724243164,0.0,1744060579.9573722,11.70126724243164,28284271247.461903
+1744060579.9769387,11.721252679824829,-5.712634523648786,1744060579.9769409,11.721252679824829,-23.9930596991462,1744060579.9769428,11.721252679824829,0.0,1744060579.9769452,11.721252679824829,56568542496.923805,1744060579.976946,11.721252679824829,0.0,1744060579.9769475,11.721252679824829,4.241413803091706e-10,1744060579.9769485,11.721252679824829,23.9930596991462,1744060579.9769495,11.721252679824829,3.455000595734934e-20,1744060579.976951,11.721252679824829,10,1744060579.9769518,11.721252679824829,0.0,1744060579.9769528,11.721252679824829,-22627416989.969524,1744060579.9769535,11.721252679824829,0.0,1744060579.976955,11.721252679824829,28284271247.461903
+1744060579.9971924,11.741298913955688,-5.712634523648786,1744060579.9971945,11.741298913955688,-23.9930596991462,1744060579.9971972,11.741298913955688,0.0,1744060579.9972,11.741298913955688,56568542496.923805,1744060579.9972014,11.741298913955688,0.0,1744060579.9972026,11.741298913955688,4.241413803091706e-10,1744060579.9972043,11.741298913955688,23.9930596991462,1744060579.9972055,11.741298913955688,3.455000595734934e-20,1744060579.9972067,11.741298913955688,10,1744060579.9972079,11.741298913955688,0.0,1744060579.997209,11.741298913955688,-22627416989.969524,1744060579.99721,11.741298913955688,0.0,1744060579.9972115,11.741298913955688,28284271247.461903
+1744060580.0169537,11.761260747909546,-5.712634523648786,1744060580.0169554,11.761260747909546,-23.9930596991462,1744060580.0169578,11.761260747909546,0.0,1744060580.0169597,11.761260747909546,56568542496.923805,1744060580.016961,11.761260747909546,0.0,1744060580.016962,11.761260747909546,4.241413803091706e-10,1744060580.0169632,11.761260747909546,23.9930596991462,1744060580.0169644,11.761260747909546,3.455000595734934e-20,1744060580.0169656,11.761260747909546,10,1744060580.0169666,11.761260747909546,0.0,1744060580.0169678,11.761260747909546,-22627416989.969524,1744060580.0169687,11.761260747909546,0.0,1744060580.0169694,11.761260747909546,28284271247.461903
+1744060580.0373306,11.781480073928833,-5.712634523648786,1744060580.0373328,11.781480073928833,-23.9930596991462,1744060580.0373352,11.781480073928833,0.0,1744060580.0373373,11.781480073928833,56568542496.923805,1744060580.0373383,11.781480073928833,0.0,1744060580.03734,11.781480073928833,4.241413803091706e-10,1744060580.037341,11.781480073928833,23.9930596991462,1744060580.0373425,11.781480073928833,3.455000595734934e-20,1744060580.0373437,11.781480073928833,10,1744060580.0373447,11.781480073928833,0.0,1744060580.037346,11.781480073928833,-22627416989.969524,1744060580.0373468,11.781480073928833,0.0,1744060580.0373642,11.781480073928833,28284271247.461903
+1744060580.0573955,11.80126428604126,-5.712634523648786,1744060580.0573974,11.80126428604126,-23.9930596991462,1744060580.0573995,11.80126428604126,0.0,1744060580.0574017,11.80126428604126,56568542496.923805,1744060580.0574026,11.80126428604126,0.0,1744060580.057404,11.80126428604126,4.241413803091706e-10,1744060580.057406,11.80126428604126,23.9930596991462,1744060580.0574079,11.80126428604126,3.455000595734934e-20,1744060580.0574095,11.80126428604126,10,1744060580.057411,11.80126428604126,0.0,1744060580.0574126,11.80126428604126,-22627416989.969524,1744060580.0574143,11.80126428604126,0.0,1744060580.057416,11.80126428604126,28284271247.461903
+1744060580.0771275,11.821256875991821,-5.712634523648786,1744060580.0771294,11.821256875991821,-23.9930596991462,1744060580.0771315,11.821256875991821,0.0,1744060580.0771341,11.821256875991821,56568542496.923805,1744060580.077135,11.821256875991821,0.0,1744060580.0771363,11.821256875991821,4.241413803091706e-10,1744060580.0771377,11.821256875991821,23.9930596991462,1744060580.077139,11.821256875991821,3.455000595734934e-20,1744060580.0771399,11.821256875991821,10,1744060580.077141,11.821256875991821,0.0,1744060580.077142,11.821256875991821,-22627416989.969524,1744060580.077143,11.821256875991821,0.0,1744060580.0771441,11.821256875991821,28284271247.461903
+1744060580.0970824,11.841267585754395,-5.712634523648786,1744060580.0970845,11.841267585754395,-23.9930596991462,1744060580.0970864,11.841267585754395,0.0,1744060580.0970888,11.841267585754395,56568542496.923805,1744060580.0970898,11.841267585754395,0.0,1744060580.0970907,11.841267585754395,4.241413803091706e-10,1744060580.0970922,11.841267585754395,23.9930596991462,1744060580.097093,11.841267585754395,3.455000595734934e-20,1744060580.097094,11.841267585754395,10,1744060580.0970953,11.841267585754395,0.0,1744060580.0970964,11.841267585754395,-22627416989.969524,1744060580.0970974,11.841267585754395,0.0,1744060580.0970986,11.841267585754395,28284271247.461903
+1744060580.1168606,11.861216068267822,-5.712634523648786,1744060580.1168625,11.861216068267822,-23.9930596991462,1744060580.1168647,11.861216068267822,0.0,1744060580.1168668,11.861216068267822,56568542496.923805,1744060580.1168683,11.861216068267822,0.0,1744060580.1168697,11.861216068267822,4.241413803091706e-10,1744060580.1168706,11.861216068267822,23.9930596991462,1744060580.1168718,11.861216068267822,3.455000595734934e-20,1744060580.116873,11.861216068267822,10,1744060580.116874,11.861216068267822,0.0,1744060580.116875,11.861216068267822,-22627416989.969524,1744060580.1168761,11.861216068267822,0.0,1744060580.1168773,11.861216068267822,28284271247.461903
+1744060580.137137,11.881229639053345,-5.712634523648786,1744060580.1371386,11.881229639053345,-23.9930596991462,1744060580.1371408,11.881229639053345,0.0,1744060580.137143,11.881229639053345,56568542496.923805,1744060580.1371439,11.881229639053345,0.0,1744060580.137145,11.881229639053345,4.241413803091706e-10,1744060580.137146,11.881229639053345,23.9930596991462,1744060580.1371472,11.881229639053345,3.455000595734934e-20,1744060580.1371484,11.881229639053345,10,1744060580.1371493,11.881229639053345,0.0,1744060580.1371505,11.881229639053345,-22627416989.969524,1744060580.1371512,11.881229639053345,0.0,1744060580.1371522,11.881229639053345,28284271247.461903
+1744060580.1572437,11.901253461837769,-5.712634523648786,1744060580.1572452,11.901253461837769,-23.9930596991462,1744060580.1572473,11.901253461837769,0.0,1744060580.1572492,11.901253461837769,56568542496.923805,1744060580.1572506,11.901253461837769,0.0,1744060580.1572518,11.901253461837769,4.241413803091706e-10,1744060580.157253,11.901253461837769,23.9930596991462,1744060580.1572542,11.901253461837769,3.455000595734934e-20,1744060580.1572552,11.901253461837769,10,1744060580.1572561,11.901253461837769,0.0,1744060580.1572573,11.901253461837769,-22627416989.969524,1744060580.1572583,11.901253461837769,0.0,1744060580.1572595,11.901253461837769,28284271247.461903
+1744060580.1771295,11.921252727508545,-5.712634523648786,1744060580.1771314,11.921252727508545,-23.9930596991462,1744060580.1771336,11.921252727508545,0.0,1744060580.1771357,11.921252727508545,56568542496.923805,1744060580.1771367,11.921252727508545,0.0,1744060580.1771379,11.921252727508545,4.241413803091706e-10,1744060580.1771393,11.921252727508545,23.9930596991462,1744060580.1771402,11.921252727508545,3.455000595734934e-20,1744060580.1771412,11.921252727508545,10,1744060580.1771424,11.921252727508545,0.0,1744060580.1771433,11.921252727508545,-22627416989.969524,1744060580.1771443,11.921252727508545,0.0,1744060580.1771452,11.921252727508545,28284271247.461903
+1744060580.1972797,11.941360473632812,-5.712634523648786,1744060580.1972816,11.941360473632812,-23.9930596991462,1744060580.1972837,11.941360473632812,0.0,1744060580.1972864,11.941360473632812,56568542496.923805,1744060580.1972878,11.941360473632812,0.0,1744060580.197289,11.941360473632812,4.241413803091706e-10,1744060580.1972902,11.941360473632812,23.9930596991462,1744060580.1972914,11.941360473632812,3.455000595734934e-20,1744060580.1972926,11.941360473632812,10,1744060580.1972933,11.941360473632812,0.0,1744060580.1972942,11.941360473632812,-22627416989.969524,1744060580.1972954,11.941360473632812,0.0,1744060580.1972964,11.941360473632812,28284271247.461903
+1744060580.2169147,11.961250305175781,-5.712634523648786,1744060580.2169168,11.961250305175781,-23.9930596991462,1744060580.216919,11.961250305175781,0.0,1744060580.2169213,11.961250305175781,56568542496.923805,1744060580.2169223,11.961250305175781,0.0,1744060580.2169237,11.961250305175781,4.241413803091706e-10,1744060580.2169247,11.961250305175781,23.9930596991462,1744060580.2169259,11.961250305175781,3.455000595734934e-20,1744060580.216927,11.961250305175781,10,1744060580.216928,11.961250305175781,0.0,1744060580.2169287,11.961250305175781,-22627416989.969524,1744060580.2169304,11.961250305175781,0.0,1744060580.216931,11.961250305175781,28284271247.461903
+1744060580.236929,11.98122525215149,-5.712634523648786,1744060580.2369308,11.98122525215149,-23.9930596991462,1744060580.2369328,11.98122525215149,0.0,1744060580.2369351,11.98122525215149,56568542496.923805,1744060580.2369363,11.98122525215149,0.0,1744060580.2369378,11.98122525215149,4.241413803091706e-10,1744060580.236939,11.98122525215149,23.9930596991462,1744060580.2369401,11.98122525215149,3.455000595734934e-20,1744060580.2369413,11.98122525215149,10,1744060580.2369423,11.98122525215149,0.0,1744060580.2369432,11.98122525215149,-22627416989.969524,1744060580.2369442,11.98122525215149,0.0,1744060580.2369454,11.98122525215149,28284271247.461903
+1744060580.2575638,12.001262187957764,-6.209957590637956,1744060580.257566,12.001262187957764,-26.260748697396334,1744060580.257568,12.001262187957764,0.0,1744060580.2575703,12.001262187957764,56568542496.923805,1744060580.2575712,12.001262187957764,0.0,1744060580.2575727,12.001262187957764,4.642288370067436e-10,1744060580.2575736,12.001262187957764,26.260748697396334,1744060580.2575748,12.001262187957764,3.781547811327417e-20,1744060580.257576,12.001262187957764,10,1744060580.257577,12.001262187957764,0.0,1744060580.257578,12.001262187957764,-22627416989.969524,1744060580.257579,12.001262187957764,0.0,1744060580.25758,12.001262187957764,28284271247.461903
+1744060580.2769148,12.021251201629639,-6.209957590637956,1744060580.276917,12.021251201629639,-26.260748697396334,1744060580.2769191,12.021251201629639,0.0,1744060580.2769213,12.021251201629639,56568542496.923805,1744060580.2769225,12.021251201629639,0.0,1744060580.2769234,12.021251201629639,4.642288370067436e-10,1744060580.2769246,12.021251201629639,26.260748697396334,1744060580.276926,12.021251201629639,3.781547811327417e-20,1744060580.276927,12.021251201629639,10,1744060580.276928,12.021251201629639,0.0,1744060580.2769291,12.021251201629639,-22627416989.969524,1744060580.27693,12.021251201629639,0.0,1744060580.276931,12.021251201629639,28284271247.461903
+1744060580.2981594,12.041281700134277,-6.209957590637956,1744060580.2981787,12.041281700134277,-26.260748697396334,1744060580.2981834,12.041281700134277,0.0,1744060580.2981882,12.041281700134277,56568542496.923805,1744060580.29819,12.041281700134277,0.0,1744060580.2981932,12.041281700134277,4.642288370067436e-10,1744060580.2981956,12.041281700134277,26.260748697396334,1744060580.2981977,12.041281700134277,3.781547811327417e-20,1744060580.2982004,12.041281700134277,10,1744060580.2982032,12.041281700134277,0.0,1744060580.2982054,12.041281700134277,-22627416989.969524,1744060580.2982075,12.041281700134277,0.0,1744060580.2982104,12.041281700134277,28284271247.461903
+1744060580.3169363,12.061230182647705,-6.209957590637956,1744060580.3169386,12.061230182647705,-26.260748697396334,1744060580.316941,12.061230182647705,0.0,1744060580.3169446,12.061230182647705,56568542496.923805,1744060580.316947,12.061230182647705,0.0,1744060580.3169491,12.061230182647705,4.642288370067436e-10,1744060580.3169513,12.061230182647705,26.260748697396334,1744060580.3169532,12.061230182647705,3.781547811327417e-20,1744060580.3169584,12.061230182647705,10,1744060580.31696,12.061230182647705,0.0,1744060580.3169613,12.061230182647705,-22627416989.969524,1744060580.3169625,12.061230182647705,0.0,1744060580.3169641,12.061230182647705,28284271247.461903
+1744060580.3372846,12.081278562545776,-6.209957590637956,1744060580.3372865,12.081278562545776,-26.260748697396334,1744060580.3372884,12.081278562545776,0.0,1744060580.3372908,12.081278562545776,56568542496.923805,1744060580.3372917,12.081278562545776,0.0,1744060580.337293,12.081278562545776,4.642288370067436e-10,1744060580.337294,12.081278562545776,26.260748697396334,1744060580.3372953,12.081278562545776,3.781547811327417e-20,1744060580.3372965,12.081278562545776,10,1744060580.3372974,12.081278562545776,0.0,1744060580.3372984,12.081278562545776,-22627416989.969524,1744060580.3372993,12.081278562545776,0.0,1744060580.3373005,12.081278562545776,28284271247.461903
+1744060580.3573363,12.101236343383789,-6.209957590637956,1744060580.3573382,12.101236343383789,-26.260748697396334,1744060580.35734,12.101236343383789,0.0,1744060580.3573422,12.101236343383789,56568542496.923805,1744060580.3573432,12.101236343383789,0.0,1744060580.3573446,12.101236343383789,4.642288370067436e-10,1744060580.3573458,12.101236343383789,26.260748697396334,1744060580.357347,12.101236343383789,3.781547811327417e-20,1744060580.3573482,12.101236343383789,10,1744060580.3573492,12.101236343383789,0.0,1744060580.35735,12.101236343383789,-22627416989.969524,1744060580.357351,12.101236343383789,0.0,1744060580.3573523,12.101236343383789,28284271247.461903
+1744060580.376921,12.121251344680786,-6.209957590637956,1744060580.3769228,12.121251344680786,-26.260748697396334,1744060580.376925,12.121251344680786,0.0,1744060580.3769271,12.121251344680786,56568542496.923805,1744060580.3769283,12.121251344680786,0.0,1744060580.3769295,12.121251344680786,4.642288370067436e-10,1744060580.3769307,12.121251344680786,26.260748697396334,1744060580.3769324,12.121251344680786,3.781547811327417e-20,1744060580.3769333,12.121251344680786,10,1744060580.3769343,12.121251344680786,0.0,1744060580.3769355,12.121251344680786,-22627416989.969524,1744060580.3769362,12.121251344680786,0.0,1744060580.3769372,12.121251344680786,28284271247.461903
+1744060580.3970654,12.141272068023682,-6.209957590637956,1744060580.3970675,12.141272068023682,-26.260748697396334,1744060580.3970695,12.141272068023682,0.0,1744060580.3970718,12.141272068023682,56568542496.923805,1744060580.3970728,12.141272068023682,0.0,1744060580.3970742,12.141272068023682,4.642288370067436e-10,1744060580.3970754,12.141272068023682,26.260748697396334,1744060580.3970768,12.141272068023682,3.781547811327417e-20,1744060580.3970778,12.141272068023682,10,1744060580.3970788,12.141272068023682,0.0,1744060580.3970797,12.141272068023682,-22627416989.969524,1744060580.397081,12.141272068023682,0.0,1744060580.3970819,12.141272068023682,28284271247.461903
+1744060580.4169312,12.161229610443115,-6.209957590637956,1744060580.416933,12.161229610443115,-26.260748697396334,1744060580.4169352,12.161229610443115,0.0,1744060580.416937,12.161229610443115,56568542496.923805,1744060580.4169383,12.161229610443115,0.0,1744060580.4169395,12.161229610443115,4.642288370067436e-10,1744060580.4169412,12.161229610443115,26.260748697396334,1744060580.4169421,12.161229610443115,3.781547811327417e-20,1744060580.416943,12.161229610443115,10,1744060580.416944,12.161229610443115,0.0,1744060580.4169452,12.161229610443115,-22627416989.969524,1744060580.4169462,12.161229610443115,0.0,1744060580.416947,12.161229610443115,28284271247.461903
+1744060580.4372249,12.181252717971802,-6.209957590637956,1744060580.4372265,12.181252717971802,-26.260748697396334,1744060580.437229,12.181252717971802,0.0,1744060580.4372308,12.181252717971802,56568542496.923805,1744060580.4372318,12.181252717971802,0.0,1744060580.437233,12.181252717971802,4.642288370067436e-10,1744060580.4372342,12.181252717971802,26.260748697396334,1744060580.437235,12.181252717971802,3.781547811327417e-20,1744060580.4372365,12.181252717971802,10,1744060580.4372375,12.181252717971802,0.0,1744060580.4372385,12.181252717971802,-22627416989.969524,1744060580.4372396,12.181252717971802,0.0,1744060580.4372406,12.181252717971802,28284271247.461903
+1744060580.457562,12.201246738433838,-6.209957590637956,1744060580.4575639,12.201246738433838,-26.260748697396334,1744060580.457566,12.201246738433838,0.0,1744060580.4575682,12.201246738433838,56568542496.923805,1744060580.4575694,12.201246738433838,0.0,1744060580.4575706,12.201246738433838,4.642288370067436e-10,1744060580.4575717,12.201246738433838,26.260748697396334,1744060580.457573,12.201246738433838,3.781547811327417e-20,1744060580.4575744,12.201246738433838,10,1744060580.4575753,12.201246738433838,0.0,1744060580.4575763,12.201246738433838,-22627416989.969524,1744060580.4575775,12.201246738433838,0.0,1744060580.4575782,12.201246738433838,28284271247.461903
+1744060580.4770007,12.221256256103516,-6.209957590637956,1744060580.4770029,12.221256256103516,-26.260748697396334,1744060580.477005,12.221256256103516,0.0,1744060580.4770074,12.221256256103516,56568542496.923805,1744060580.4770083,12.221256256103516,0.0,1744060580.4770093,12.221256256103516,4.642288370067436e-10,1744060580.4770107,12.221256256103516,26.260748697396334,1744060580.4770122,12.221256256103516,3.781547811327417e-20,1744060580.4770133,12.221256256103516,10,1744060580.4770143,12.221256256103516,0.0,1744060580.4770153,12.221256256103516,-22627416989.969524,1744060580.4770162,12.221256256103516,0.0,1744060580.4770174,12.221256256103516,28284271247.461903
+1744060580.4969652,12.241264343261719,-6.209957590637956,1744060580.4969668,12.241264343261719,-26.260748697396334,1744060580.4969692,12.241264343261719,0.0,1744060580.4969714,12.241264343261719,56568542496.923805,1744060580.4969726,12.241264343261719,0.0,1744060580.4969738,12.241264343261719,4.642288370067436e-10,1744060580.4969752,12.241264343261719,26.260748697396334,1744060580.4969764,12.241264343261719,3.781547811327417e-20,1744060580.4969773,12.241264343261719,10,1744060580.4969785,12.241264343261719,0.0,1744060580.4969795,12.241264343261719,-22627416989.969524,1744060580.4969807,12.241264343261719,0.0,1744060580.4969819,12.241264343261719,28284271247.461903
+1744060580.5169606,12.261259317398071,-6.209957590637956,1744060580.5169623,12.261259317398071,-26.260748697396334,1744060580.5169644,12.261259317398071,0.0,1744060580.5169666,12.261259317398071,56568542496.923805,1744060580.5169678,12.261259317398071,0.0,1744060580.516969,12.261259317398071,4.642288370067436e-10,1744060580.5169704,12.261259317398071,26.260748697396334,1744060580.5169716,12.261259317398071,3.781547811327417e-20,1744060580.5169725,12.261259317398071,10,1744060580.5169737,12.261259317398071,0.0,1744060580.5169747,12.261259317398071,-22627416989.969524,1744060580.5169756,12.261259317398071,0.0,1744060580.5169766,12.261259317398071,28284271247.461903
+1744060580.5369182,12.281249046325684,-6.209957590637956,1744060580.5369205,12.281249046325684,-26.260748697396334,1744060580.5369227,12.281249046325684,0.0,1744060580.5369248,12.281249046325684,56568542496.923805,1744060580.5369258,12.281249046325684,0.0,1744060580.536927,12.281249046325684,4.642288370067436e-10,1744060580.5369282,12.281249046325684,26.260748697396334,1744060580.5369294,12.281249046325684,3.781547811327417e-20,1744060580.5369303,12.281249046325684,10,1744060580.5369313,12.281249046325684,0.0,1744060580.5369327,12.281249046325684,-22627416989.969524,1744060580.5369337,12.281249046325684,0.0,1744060580.5369346,12.281249046325684,28284271247.461903
+1744060580.5583594,12.301307678222656,-6.209957590637956,1744060580.5583625,12.301307678222656,-26.260748697396334,1744060580.5583649,12.301307678222656,0.0,1744060580.5583675,12.301307678222656,56568542496.923805,1744060580.558386,12.301307678222656,0.0,1744060580.5583878,12.301307678222656,4.642288370067436e-10,1744060580.5583897,12.301307678222656,26.260748697396334,1744060580.558391,12.301307678222656,3.781547811327417e-20,1744060580.5583923,12.301307678222656,10,1744060580.5583937,12.301307678222656,0.0,1744060580.558395,12.301307678222656,-22627416989.969524,1744060580.5583959,12.301307678222656,0.0,1744060580.5583968,12.301307678222656,28284271247.461903
+1744060580.5769987,12.321293354034424,-6.209957590637956,1744060580.5770004,12.321293354034424,-26.260748697396334,1744060580.5770025,12.321293354034424,0.0,1744060580.577005,12.321293354034424,56568542496.923805,1744060580.5770056,12.321293354034424,0.0,1744060580.5770068,12.321293354034424,4.642288370067436e-10,1744060580.5770085,12.321293354034424,26.260748697396334,1744060580.5770094,12.321293354034424,3.781547811327417e-20,1744060580.5770106,12.321293354034424,10,1744060580.5770118,12.321293354034424,0.0,1744060580.5770125,12.321293354034424,-22627416989.969524,1744060580.5770137,12.321293354034424,0.0,1744060580.577015,12.321293354034424,28284271247.461903
+1744060580.5972784,12.341291904449463,-6.209957590637956,1744060580.5972812,12.341291904449463,-26.260748697396334,1744060580.5973034,12.341291904449463,0.0,1744060580.5973072,12.341291904449463,56568542496.923805,1744060580.5973086,12.341291904449463,0.0,1744060580.59731,12.341291904449463,4.642288370067436e-10,1744060580.597312,12.341291904449463,26.260748697396334,1744060580.5973146,12.341291904449463,3.781547811327417e-20,1744060580.597316,12.341291904449463,10,1744060580.5973175,12.341291904449463,0.0,1744060580.5973186,12.341291904449463,-22627416989.969524,1744060580.5973198,12.341291904449463,0.0,1744060580.597321,12.341291904449463,28284271247.461903
+1744060580.617085,12.361281156539917,-6.209957590637956,1744060580.6170866,12.361281156539917,-26.260748697396334,1744060580.617089,12.361281156539917,0.0,1744060580.6170912,12.361281156539917,56568542496.923805,1744060580.6170921,12.361281156539917,0.0,1744060580.6170933,12.361281156539917,4.642288370067436e-10,1744060580.6170948,12.361281156539917,26.260748697396334,1744060580.6170957,12.361281156539917,3.781547811327417e-20,1744060580.617097,12.361281156539917,10,1744060580.617098,12.361281156539917,0.0,1744060580.6170988,12.361281156539917,-22627416989.969524,1744060580.6170998,12.361281156539917,0.0,1744060580.6171007,12.361281156539917,28284271247.461903
+1744060580.6372895,12.381270408630371,-6.209957590637956,1744060580.6372914,12.381270408630371,-26.260748697396334,1744060580.6372938,12.381270408630371,0.0,1744060580.637296,12.381270408630371,56568542496.923805,1744060580.637297,12.381270408630371,0.0,1744060580.637298,12.381270408630371,4.642288370067436e-10,1744060580.6372995,12.381270408630371,26.260748697396334,1744060580.6373007,12.381270408630371,3.781547811327417e-20,1744060580.6373017,12.381270408630371,10,1744060580.6373026,12.381270408630371,0.0,1744060580.6373036,12.381270408630371,-22627416989.969524,1744060580.6373045,12.381270408630371,0.0,1744060580.6373055,12.381270408630371,28284271247.461903
+1744060580.6573102,12.4012610912323,-6.209957590637956,1744060580.657312,12.4012610912323,-26.260748697396334,1744060580.657314,12.4012610912323,0.0,1744060580.6573164,12.4012610912323,56568542496.923805,1744060580.6573174,12.4012610912323,0.0,1744060580.6573184,12.4012610912323,4.642288370067436e-10,1744060580.6573198,12.4012610912323,26.260748697396334,1744060580.657321,12.4012610912323,3.781547811327417e-20,1744060580.657322,12.4012610912323,10,1744060580.6573231,12.4012610912323,0.0,1744060580.657324,12.4012610912323,-22627416989.969524,1744060580.657325,12.4012610912323,0.0,1744060580.657326,12.4012610912323,28284271247.461903
+1744060580.6769612,12.421249628067017,-6.209957590637956,1744060580.6769633,12.421249628067017,-26.260748697396334,1744060580.676966,12.421249628067017,0.0,1744060580.6769679,12.421249628067017,56568542496.923805,1744060580.676969,12.421249628067017,0.0,1744060580.6769702,12.421249628067017,4.642288370067436e-10,1744060580.6769712,12.421249628067017,26.260748697396334,1744060580.6769726,12.421249628067017,3.781547811327417e-20,1744060580.6769736,12.421249628067017,10,1744060580.6769743,12.421249628067017,0.0,1744060580.6769753,12.421249628067017,-22627416989.969524,1744060580.6769764,12.421249628067017,0.0,1744060580.6769774,12.421249628067017,28284271247.461903
+1744060580.6971843,12.441280603408813,-6.209957590637956,1744060580.6971865,12.441280603408813,-26.260748697396334,1744060580.697189,12.441280603408813,0.0,1744060580.6971915,12.441280603408813,56568542496.923805,1744060580.6971924,12.441280603408813,0.0,1744060580.6971936,12.441280603408813,4.642288370067436e-10,1744060580.6971953,12.441280603408813,26.260748697396334,1744060580.6971965,12.441280603408813,3.781547811327417e-20,1744060580.6971977,12.441280603408813,10,1744060580.6971989,12.441280603408813,0.0,1744060580.6971996,12.441280603408813,-22627416989.969524,1744060580.6972005,12.441280603408813,0.0,1744060580.697202,12.441280603408813,28284271247.461903
+1744060580.7169569,12.461259365081787,-6.209957590637956,1744060580.7169588,12.461259365081787,-26.260748697396334,1744060580.7169607,12.461259365081787,0.0,1744060580.716963,12.461259365081787,56568542496.923805,1744060580.716964,12.461259365081787,0.0,1744060580.7169652,12.461259365081787,4.642288370067436e-10,1744060580.7169666,12.461259365081787,26.260748697396334,1744060580.7169678,12.461259365081787,3.781547811327417e-20,1744060580.716969,12.461259365081787,10,1744060580.71697,12.461259365081787,0.0,1744060580.716971,12.461259365081787,-22627416989.969524,1744060580.7169719,12.461259365081787,0.0,1744060580.7169728,12.461259365081787,28284271247.461903
+1744060580.7371504,12.481369733810425,-6.209957590637956,1744060580.7371523,12.481369733810425,-26.260748697396334,1744060580.7371542,12.481369733810425,0.0,1744060580.7371564,12.481369733810425,56568542496.923805,1744060580.7371573,12.481369733810425,0.0,1744060580.7371585,12.481369733810425,4.642288370067436e-10,1744060580.73716,12.481369733810425,26.260748697396334,1744060580.737161,12.481369733810425,3.781547811327417e-20,1744060580.7371624,12.481369733810425,10,1744060580.7371633,12.481369733810425,0.0,1744060580.7371643,12.481369733810425,-22627416989.969524,1744060580.7371652,12.481369733810425,0.0,1744060580.7371664,12.481369733810425,28284271247.461903
+1744060580.7573037,12.50125241279602,-6.61021968737067,1744060580.7573059,12.50125241279602,-28.152008113984788,1744060580.757308,12.50125241279602,0.0,1744060580.7573102,12.50125241279602,56568542496.923805,1744060580.7573113,12.50125241279602,0.0,1744060580.7573128,12.50125241279602,4.976618959596853e-10,1744060580.7573137,12.50125241279602,28.152008113984788,1744060580.7573152,12.50125241279602,4.053889167179735e-20,1744060580.7573164,12.50125241279602,10,1744060580.7573173,12.50125241279602,0.0,1744060580.7573183,12.50125241279602,-22627416989.969524,1744060580.7573192,12.50125241279602,0.0,1744060580.7573202,12.50125241279602,28284271247.461903
+1744060580.77703,12.521264553070068,-6.61021968737067,1744060580.777032,12.521264553070068,-28.152008113984788,1744060580.777034,12.521264553070068,0.0,1744060580.777036,12.521264553070068,56568542496.923805,1744060580.7770371,12.521264553070068,0.0,1744060580.7770383,12.521264553070068,4.976618959596853e-10,1744060580.7770395,12.521264553070068,28.152008113984788,1744060580.777041,12.521264553070068,4.053889167179735e-20,1744060580.7770422,12.521264553070068,10,1744060580.7770429,12.521264553070068,0.0,1744060580.777044,12.521264553070068,-22627416989.969524,1744060580.7770452,12.521264553070068,0.0,1744060580.7770462,12.521264553070068,28284271247.461903
+1744060580.7969344,12.54122805595398,-6.61021968737067,1744060580.7969363,12.54122805595398,-28.152008113984788,1744060580.7969382,12.54122805595398,0.0,1744060580.7969406,12.54122805595398,56568542496.923805,1744060580.7969415,12.54122805595398,0.0,1744060580.796943,12.54122805595398,4.976618959596853e-10,1744060580.796944,12.54122805595398,28.152008113984788,1744060580.796945,12.54122805595398,4.053889167179735e-20,1744060580.7969463,12.54122805595398,10,1744060580.7969472,12.54122805595398,0.0,1744060580.796948,12.54122805595398,-22627416989.969524,1744060580.796949,12.54122805595398,0.0,1744060580.79695,12.54122805595398,28284271247.461903
+1744060580.8170161,12.56126093864441,-6.61021968737067,1744060580.8170178,12.56126093864441,-28.152008113984788,1744060580.81702,12.56126093864441,0.0,1744060580.8170218,12.56126093864441,56568542496.923805,1744060580.817023,12.56126093864441,0.0,1744060580.8170242,12.56126093864441,4.976618959596853e-10,1744060580.8170254,12.56126093864441,28.152008113984788,1744060580.8170269,12.56126093864441,4.053889167179735e-20,1744060580.8170278,12.56126093864441,10,1744060580.8170285,12.56126093864441,0.0,1744060580.8170297,12.56126093864441,-22627416989.969524,1744060580.8170307,12.56126093864441,0.0,1744060580.8170316,12.56126093864441,28284271247.461903
+1744060580.8370216,12.581335544586182,-6.61021968737067,1744060580.8370237,12.581335544586182,-28.152008113984788,1744060580.8370261,12.581335544586182,0.0,1744060580.837028,12.581335544586182,56568542496.923805,1744060580.8370292,12.581335544586182,0.0,1744060580.8370304,12.581335544586182,4.976618959596853e-10,1744060580.8370316,12.581335544586182,28.152008113984788,1744060580.8370328,12.581335544586182,4.053889167179735e-20,1744060580.837034,12.581335544586182,10,1744060580.837035,12.581335544586182,0.0,1744060580.837036,12.581335544586182,-22627416989.969524,1744060580.8370368,12.581335544586182,0.0,1744060580.8370438,12.581335544586182,28284271247.461903
+1744060580.85749,12.601266860961914,-6.61021968737067,1744060580.8574922,12.601266860961914,-28.152008113984788,1744060580.8574944,12.601266860961914,0.0,1744060580.8574963,12.601266860961914,56568542496.923805,1744060580.8574975,12.601266860961914,0.0,1744060580.857499,12.601266860961914,4.976618959596853e-10,1744060580.8575,12.601266860961914,28.152008113984788,1744060580.8575015,12.601266860961914,4.053889167179735e-20,1744060580.8575027,12.601266860961914,10,1744060580.8575037,12.601266860961914,0.0,1744060580.857505,12.601266860961914,-22627416989.969524,1744060580.857506,12.601266860961914,0.0,1744060580.8575068,12.601266860961914,28284271247.461903
+1744060580.8769352,12.621248722076416,-6.61021968737067,1744060580.876937,12.621248722076416,-28.152008113984788,1744060580.8769393,12.621248722076416,0.0,1744060580.8769412,12.621248722076416,56568542496.923805,1744060580.8769424,12.621248722076416,0.0,1744060580.8769436,12.621248722076416,4.976618959596853e-10,1744060580.8769448,12.621248722076416,28.152008113984788,1744060580.876946,12.621248722076416,4.053889167179735e-20,1744060580.876947,12.621248722076416,10,1744060580.8769479,12.621248722076416,0.0,1744060580.8769493,12.621248722076416,-22627416989.969524,1744060580.8769503,12.621248722076416,0.0,1744060580.8769512,12.621248722076416,28284271247.461903
+1744060580.8973024,12.641264200210571,-6.61021968737067,1744060580.8973043,12.641264200210571,-28.152008113984788,1744060580.8973067,12.641264200210571,0.0,1744060580.8973086,12.641264200210571,56568542496.923805,1744060580.8973098,12.641264200210571,0.0,1744060580.897311,12.641264200210571,4.976618959596853e-10,1744060580.8973122,12.641264200210571,28.152008113984788,1744060580.8973134,12.641264200210571,4.053889167179735e-20,1744060580.8973145,12.641264200210571,10,1744060580.8973153,12.641264200210571,0.0,1744060580.8973165,12.641264200210571,-22627416989.969524,1744060580.8973174,12.641264200210571,0.0,1744060580.8973184,12.641264200210571,28284271247.461903
+1744060580.9168658,12.661218166351318,-6.61021968737067,1744060580.9168673,12.661218166351318,-28.152008113984788,1744060580.9168694,12.661218166351318,0.0,1744060580.9168718,12.661218166351318,56568542496.923805,1744060580.9168727,12.661218166351318,0.0,1744060580.916874,12.661218166351318,4.976618959596853e-10,1744060580.9168754,12.661218166351318,28.152008113984788,1744060580.9168763,12.661218166351318,4.053889167179735e-20,1744060580.9168773,12.661218166351318,10,1744060580.9168782,12.661218166351318,0.0,1744060580.9168794,12.661218166351318,-22627416989.969524,1744060580.9168801,12.661218166351318,0.0,1744060580.916881,12.661218166351318,28284271247.461903
+1744060580.9369612,12.681257963180542,-6.61021968737067,1744060580.936963,12.681257963180542,-28.152008113984788,1744060580.9369652,12.681257963180542,0.0,1744060580.9369674,12.681257963180542,56568542496.923805,1744060580.9369686,12.681257963180542,0.0,1744060580.9369698,12.681257963180542,4.976618959596853e-10,1744060580.936971,12.681257963180542,28.152008113984788,1744060580.9369724,12.681257963180542,4.053889167179735e-20,1744060580.9369733,12.681257963180542,10,1744060580.9369743,12.681257963180542,0.0,1744060580.9369755,12.681257963180542,-22627416989.969524,1744060580.9369764,12.681257963180542,0.0,1744060580.9369774,12.681257963180542,28284271247.461903
+1744060580.9571934,12.70123028755188,-6.61021968737067,1744060580.957195,12.70123028755188,-28.152008113984788,1744060580.957197,12.70123028755188,0.0,1744060580.9571993,12.70123028755188,56568542496.923805,1744060580.9572003,12.70123028755188,0.0,1744060580.9572015,12.70123028755188,4.976618959596853e-10,1744060580.9572027,12.70123028755188,28.152008113984788,1744060580.9572036,12.70123028755188,4.053889167179735e-20,1744060580.957205,12.70123028755188,10,1744060580.957206,12.70123028755188,0.0,1744060580.957207,12.70123028755188,-22627416989.969524,1744060580.9572082,12.70123028755188,0.0,1744060580.9572089,12.70123028755188,28284271247.461903
+1744060580.9770417,12.721263647079468,-6.61021968737067,1744060580.9770436,12.721263647079468,-28.152008113984788,1744060580.977046,12.721263647079468,0.0,1744060580.9770482,12.721263647079468,56568542496.923805,1744060580.977049,12.721263647079468,0.0,1744060580.9770503,12.721263647079468,4.976618959596853e-10,1744060580.977052,12.721263647079468,28.152008113984788,1744060580.977053,12.721263647079468,4.053889167179735e-20,1744060580.9770539,12.721263647079468,10,1744060580.977055,12.721263647079468,0.0,1744060580.9770558,12.721263647079468,-22627416989.969524,1744060580.9770567,12.721263647079468,0.0,1744060580.977058,12.721263647079468,28284271247.461903
+1744060580.9971642,12.741284370422363,-6.61021968737067,1744060580.9971666,12.741284370422363,-28.152008113984788,1744060580.9971685,12.741284370422363,0.0,1744060580.9971712,12.741284370422363,56568542496.923805,1744060580.997172,12.741284370422363,0.0,1744060580.9971738,12.741284370422363,4.976618959596853e-10,1744060580.997175,12.741284370422363,28.152008113984788,1744060580.9971764,12.741284370422363,4.053889167179735e-20,1744060580.9971774,12.741284370422363,10,1744060580.9971783,12.741284370422363,0.0,1744060580.9971795,12.741284370422363,-22627416989.969524,1744060580.9971805,12.741284370422363,0.0,1744060580.9971817,12.741284370422363,28284271247.461903
+1744060581.0173068,12.761234760284424,-6.61021968737067,1744060581.017309,12.761234760284424,-28.152008113984788,1744060581.0173113,12.761234760284424,0.0,1744060581.0173137,12.761234760284424,56568542496.923805,1744060581.017315,12.761234760284424,0.0,1744060581.017316,12.761234760284424,4.976618959596853e-10,1744060581.0173175,12.761234760284424,28.152008113984788,1744060581.0173187,12.761234760284424,4.053889167179735e-20,1744060581.0173202,12.761234760284424,10,1744060581.017321,12.761234760284424,0.0,1744060581.017322,12.761234760284424,-22627416989.969524,1744060581.0173233,12.761234760284424,0.0,1744060581.0173242,12.761234760284424,28284271247.461903
+1744060581.0369406,12.781249761581421,-6.61021968737067,1744060581.0369422,12.781249761581421,-28.152008113984788,1744060581.0369446,12.781249761581421,0.0,1744060581.0369468,12.781249761581421,56568542496.923805,1744060581.0369477,12.781249761581421,0.0,1744060581.0369487,12.781249761581421,4.976618959596853e-10,1744060581.03695,12.781249761581421,28.152008113984788,1744060581.036951,12.781249761581421,4.053889167179735e-20,1744060581.0369523,12.781249761581421,10,1744060581.0369534,12.781249761581421,0.0,1744060581.0369542,12.781249761581421,-22627416989.969524,1744060581.036955,12.781249761581421,0.0,1744060581.036956,12.781249761581421,28284271247.461903
+1744060581.0573049,12.801230430603027,-6.61021968737067,1744060581.057308,12.801230430603027,-28.152008113984788,1744060581.0573118,12.801230430603027,0.0,1744060581.0573158,12.801230430603027,56568542496.923805,1744060581.057318,12.801230430603027,0.0,1744060581.0573199,12.801230430603027,4.976618959596853e-10,1744060581.057323,12.801230430603027,28.152008113984788,1744060581.0573254,12.801230430603027,4.053889167179735e-20,1744060581.0573287,12.801230430603027,10,1744060581.0573323,12.801230430603027,0.0,1744060581.0573342,12.801230430603027,-22627416989.969524,1744060581.0573368,12.801230430603027,0.0,1744060581.057339,12.801230430603027,28284271247.461903
+1744060581.0769114,12.821248769760132,-6.61021968737067,1744060581.076913,12.821248769760132,-28.152008113984788,1744060581.0769155,12.821248769760132,0.0,1744060581.0769174,12.821248769760132,56568542496.923805,1744060581.0769186,12.821248769760132,0.0,1744060581.0769196,12.821248769760132,4.976618959596853e-10,1744060581.0769215,12.821248769760132,28.152008113984788,1744060581.0769224,12.821248769760132,4.053889167179735e-20,1744060581.0769236,12.821248769760132,10,1744060581.0769243,12.821248769760132,0.0,1744060581.0769255,12.821248769760132,-22627416989.969524,1744060581.0769265,12.821248769760132,0.0,1744060581.0769274,12.821248769760132,28284271247.461903
+1744060581.0970643,12.841247797012329,-6.61021968737067,1744060581.097066,12.841247797012329,-28.152008113984788,1744060581.097068,12.841247797012329,0.0,1744060581.0970702,12.841247797012329,56568542496.923805,1744060581.0970714,12.841247797012329,0.0,1744060581.0970726,12.841247797012329,4.976618959596853e-10,1744060581.097074,12.841247797012329,28.152008113984788,1744060581.0970752,12.841247797012329,4.053889167179735e-20,1744060581.0970762,12.841247797012329,10,1744060581.0970771,12.841247797012329,0.0,1744060581.0970783,12.841247797012329,-22627416989.969524,1744060581.0970793,12.841247797012329,0.0,1744060581.09708,12.841247797012329,28284271247.461903
+1744060581.116965,12.86127781867981,-6.61021968737067,1744060581.116967,12.86127781867981,-28.152008113984788,1744060581.116969,12.86127781867981,0.0,1744060581.116971,12.86127781867981,56568542496.923805,1744060581.116972,12.86127781867981,0.0,1744060581.1169734,12.86127781867981,4.976618959596853e-10,1744060581.1169744,12.86127781867981,28.152008113984788,1744060581.1169753,12.86127781867981,4.053889167179735e-20,1744060581.1169765,12.86127781867981,10,1744060581.1169775,12.86127781867981,0.0,1744060581.1169784,12.86127781867981,-22627416989.969524,1744060581.1169791,12.86127781867981,0.0,1744060581.1169803,12.86127781867981,28284271247.461903
+1744060581.1369224,12.88124942779541,-6.61021968737067,1744060581.136925,12.88124942779541,-28.152008113984788,1744060581.1369278,12.88124942779541,0.0,1744060581.13693,12.88124942779541,56568542496.923805,1744060581.1369312,12.88124942779541,0.0,1744060581.1369324,12.88124942779541,4.976618959596853e-10,1744060581.1369336,12.88124942779541,28.152008113984788,1744060581.1369348,12.88124942779541,4.053889167179735e-20,1744060581.1369357,12.88124942779541,10,1744060581.1369367,12.88124942779541,0.0,1744060581.1369376,12.88124942779541,-22627416989.969524,1744060581.1369386,12.88124942779541,0.0,1744060581.1369395,12.88124942779541,28284271247.461903
+1744060581.157399,12.901264429092407,-6.61021968737067,1744060581.1574008,12.901264429092407,-28.152008113984788,1744060581.157403,12.901264429092407,0.0,1744060581.1574054,12.901264429092407,56568542496.923805,1744060581.1574066,12.901264429092407,0.0,1744060581.1574078,12.901264429092407,4.976618959596853e-10,1744060581.157409,12.901264429092407,28.152008113984788,1744060581.1574104,12.901264429092407,4.053889167179735e-20,1744060581.1574116,12.901264429092407,10,1744060581.1574125,12.901264429092407,0.0,1744060581.157414,12.901264429092407,-22627416989.969524,1744060581.157415,12.901264429092407,0.0,1744060581.1574159,12.901264429092407,28284271247.461903
+1744060581.1769066,12.921247720718384,-6.61021968737067,1744060581.1769087,12.921247720718384,-28.152008113984788,1744060581.1769109,12.921247720718384,0.0,1744060581.1769133,12.921247720718384,56568542496.923805,1744060581.1769142,12.921247720718384,0.0,1744060581.1769152,12.921247720718384,4.976618959596853e-10,1744060581.1769164,12.921247720718384,28.152008113984788,1744060581.1769176,12.921247720718384,4.053889167179735e-20,1744060581.1769185,12.921247720718384,10,1744060581.1769197,12.921247720718384,0.0,1744060581.1769207,12.921247720718384,-22627416989.969524,1744060581.1769216,12.921247720718384,0.0,1744060581.1769226,12.921247720718384,28284271247.461903
+1744060581.1969347,12.94123125076294,-6.61021968737067,1744060581.1969364,12.94123125076294,-28.152008113984788,1744060581.1969385,12.94123125076294,0.0,1744060581.1969407,12.94123125076294,56568542496.923805,1744060581.1969416,12.94123125076294,0.0,1744060581.1969428,12.94123125076294,4.976618959596853e-10,1744060581.1969442,12.94123125076294,28.152008113984788,1744060581.1969452,12.94123125076294,4.053889167179735e-20,1744060581.1969461,12.94123125076294,10,1744060581.196947,12.94123125076294,0.0,1744060581.1969483,12.94123125076294,-22627416989.969524,1744060581.1969492,12.94123125076294,0.0,1744060581.1969502,12.94123125076294,28284271247.461903
+1744060581.2171667,12.961251020431519,-6.61021968737067,1744060581.2171686,12.961251020431519,-28.152008113984788,1744060581.2171707,12.961251020431519,0.0,1744060581.217173,12.961251020431519,56568542496.923805,1744060581.2171738,12.961251020431519,0.0,1744060581.217175,12.961251020431519,4.976618959596853e-10,1744060581.2171764,12.961251020431519,28.152008113984788,1744060581.2171776,12.961251020431519,4.053889167179735e-20,1744060581.2171788,12.961251020431519,10,1744060581.2171795,12.961251020431519,0.0,1744060581.2171807,12.961251020431519,-22627416989.969524,1744060581.2171817,12.961251020431519,0.0,1744060581.2171824,12.961251020431519,28284271247.461903
+1744060581.2369032,12.981245756149292,-6.61021968737067,1744060581.2369049,12.981245756149292,-28.152008113984788,1744060581.236907,12.981245756149292,0.0,1744060581.2369096,12.981245756149292,56568542496.923805,1744060581.2369106,12.981245756149292,0.0,1744060581.2369115,12.981245756149292,4.976618959596853e-10,1744060581.236913,12.981245756149292,28.152008113984788,1744060581.236914,12.981245756149292,4.053889167179735e-20,1744060581.2369149,12.981245756149292,10,1744060581.236916,12.981245756149292,0.0,1744060581.236917,12.981245756149292,-22627416989.969524,1744060581.236918,12.981245756149292,0.0,1744060581.236919,12.981245756149292,28284271247.461903
+1744060581.2578104,13.00129222869873,-6.920256571651293,1744060581.2578127,13.00129222869873,-29.638579804355672,1744060581.2578158,13.00129222869873,0.0,1744060581.2578192,13.00129222869873,56568542496.923805,1744060581.2578206,13.00129222869873,0.0,1744060581.2578232,13.00129222869873,5.239410190273439e-10,1744060581.2578247,13.00129222869873,29.638579804355675,1744060581.257826,13.00129222869873,4.267955490481195e-20,1744060581.2578273,13.00129222869873,10,1744060581.2578282,13.00129222869873,0.0,1744060581.2578292,13.00129222869873,-22627416989.969524,1744060581.2578304,13.00129222869873,0.0,1744060581.2578313,13.00129222869873,28284271247.461903
+1744060581.2769682,13.02122688293457,-6.920256571651293,1744060581.2769701,13.02122688293457,-29.638579804355672,1744060581.2769725,13.02122688293457,0.0,1744060581.2769747,13.02122688293457,56568542496.923805,1744060581.2769756,13.02122688293457,0.0,1744060581.2769768,13.02122688293457,5.239410190273439e-10,1744060581.2769785,13.02122688293457,29.638579804355675,1744060581.2769797,13.02122688293457,4.267955490481195e-20,1744060581.2769809,13.02122688293457,10,1744060581.276982,13.02122688293457,0.0,1744060581.276983,13.02122688293457,-22627416989.969524,1744060581.276984,13.02122688293457,0.0,1744060581.276985,13.02122688293457,28284271247.461903
+1744060581.2970593,13.041229486465454,-6.920256571651293,1744060581.2970617,13.041229486465454,-29.638579804355672,1744060581.2970645,13.041229486465454,0.0,1744060581.2970672,13.041229486465454,56568542496.923805,1744060581.2970686,13.041229486465454,0.0,1744060581.29707,13.041229486465454,5.239410190273439e-10,1744060581.2970717,13.041229486465454,29.638579804355675,1744060581.2970731,13.041229486465454,4.267955490481195e-20,1744060581.2970748,13.041229486465454,10,1744060581.297076,13.041229486465454,0.0,1744060581.297077,13.041229486465454,-22627416989.969524,1744060581.2970784,13.041229486465454,0.0,1744060581.2970796,13.041229486465454,28284271247.461903
+1744060581.3170435,13.061230659484863,-6.920256571651293,1744060581.3170457,13.061230659484863,-29.638579804355672,1744060581.3170485,13.061230659484863,0.0,1744060581.3170512,13.061230659484863,56568542496.923805,1744060581.3170524,13.061230659484863,0.0,1744060581.317054,13.061230659484863,5.239410190273439e-10,1744060581.3170555,13.061230659484863,29.638579804355675,1744060581.3170571,13.061230659484863,4.267955490481195e-20,1744060581.3170586,13.061230659484863,10,1744060581.3170598,13.061230659484863,0.0,1744060581.3170612,13.061230659484863,-22627416989.969524,1744060581.3170621,13.061230659484863,0.0,1744060581.3170636,13.061230659484863,28284271247.461903
+1744060581.3369927,13.08121943473816,-6.920256571651293,1744060581.3369954,13.08121943473816,-29.638579804355672,1744060581.3369985,13.08121943473816,0.0,1744060581.3370013,13.08121943473816,56568542496.923805,1744060581.3370025,13.08121943473816,0.0,1744060581.3370042,13.08121943473816,5.239410190273439e-10,1744060581.337006,13.08121943473816,29.638579804355675,1744060581.3370073,13.08121943473816,4.267955490481195e-20,1744060581.337009,13.08121943473816,10,1744060581.3370104,13.08121943473816,0.0,1744060581.3370113,13.08121943473816,-22627416989.969524,1744060581.3370128,13.08121943473816,0.0,1744060581.3370142,13.08121943473816,28284271247.461903
+1744060581.3585744,13.101288318634033,-6.920256571651293,1744060581.358578,13.101288318634033,-29.638579804355672,1744060581.358581,13.101288318634033,0.0,1744060581.3585844,13.101288318634033,56568542496.923805,1744060581.3585856,13.101288318634033,0.0,1744060581.3585877,13.101288318634033,5.239410190273439e-10,1744060581.35859,13.101288318634033,29.638579804355675,1744060581.3585913,13.101288318634033,4.267955490481195e-20,1744060581.3585927,13.101288318634033,10,1744060581.3585944,13.101288318634033,0.0,1744060581.3585956,13.101288318634033,-22627416989.969524,1744060581.358597,13.101288318634033,0.0,1744060581.3585985,13.101288318634033,28284271247.461903
+1744060581.3770785,13.121260404586792,-6.920256571651293,1744060581.3770812,13.121260404586792,-29.638579804355672,1744060581.377084,13.121260404586792,0.0,1744060581.3770866,13.121260404586792,56568542496.923805,1744060581.377088,13.121260404586792,0.0,1744060581.3770895,13.121260404586792,5.239410190273439e-10,1744060581.3770912,13.121260404586792,29.638579804355675,1744060581.3770926,13.121260404586792,4.267955490481195e-20,1744060581.377094,13.121260404586792,10,1744060581.3770955,13.121260404586792,0.0,1744060581.3770967,13.121260404586792,-22627416989.969524,1744060581.377098,13.121260404586792,0.0,1744060581.3770995,13.121260404586792,28284271247.461903
+1744060581.397043,13.141229391098022,-6.920256571651293,1744060581.3970451,13.141229391098022,-29.638579804355672,1744060581.3970482,13.141229391098022,0.0,1744060581.397051,13.141229391098022,56568542496.923805,1744060581.3970525,13.141229391098022,0.0,1744060581.397054,13.141229391098022,5.239410190273439e-10,1744060581.3970554,13.141229391098022,29.638579804355675,1744060581.397057,13.141229391098022,4.267955490481195e-20,1744060581.3970585,13.141229391098022,10,1744060581.3970597,13.141229391098022,0.0,1744060581.3970609,13.141229391098022,-22627416989.969524,1744060581.397062,13.141229391098022,0.0,1744060581.3970635,13.141229391098022,28284271247.461903
+1744060581.4170508,13.161254167556763,-6.920256571651293,1744060581.4170532,13.161254167556763,-29.638579804355672,1744060581.4170558,13.161254167556763,0.0,1744060581.4170585,13.161254167556763,56568542496.923805,1744060581.41706,13.161254167556763,0.0,1744060581.4170616,13.161254167556763,5.239410190273439e-10,1744060581.4170632,13.161254167556763,29.638579804355675,1744060581.4170647,13.161254167556763,4.267955490481195e-20,1744060581.417066,13.161254167556763,10,1744060581.4170673,13.161254167556763,0.0,1744060581.4170685,13.161254167556763,-22627416989.969524,1744060581.41707,13.161254167556763,0.0,1744060581.417071,13.161254167556763,28284271247.461903
+1744060581.4371371,13.18127703666687,-6.920256571651293,1744060581.4371395,13.18127703666687,-29.638579804355672,1744060581.4371424,13.18127703666687,0.0,1744060581.437145,13.18127703666687,56568542496.923805,1744060581.4371464,13.18127703666687,0.0,1744060581.437148,13.18127703666687,5.239410190273439e-10,1744060581.4371498,13.18127703666687,29.638579804355675,1744060581.437151,13.18127703666687,4.267955490481195e-20,1744060581.4371526,13.18127703666687,10,1744060581.4371538,13.18127703666687,0.0,1744060581.437155,13.18127703666687,-22627416989.969524,1744060581.4371562,13.18127703666687,0.0,1744060581.4371574,13.18127703666687,28284271247.461903
+1744060581.4579642,13.201273202896118,-6.920256571651293,1744060581.4579673,13.201273202896118,-29.638579804355672,1744060581.4579701,13.201273202896118,0.0,1744060581.457974,13.201273202896118,56568542496.923805,1744060581.4579759,13.201273202896118,0.0,1744060581.4579778,13.201273202896118,5.239410190273439e-10,1744060581.45798,13.201273202896118,29.638579804355675,1744060581.4579813,13.201273202896118,4.267955490481195e-20,1744060581.4579833,13.201273202896118,10,1744060581.4579847,13.201273202896118,0.0,1744060581.4579866,13.201273202896118,-22627416989.969524,1744060581.457988,13.201273202896118,0.0,1744060581.4579895,13.201273202896118,28284271247.461903
+1744060581.4770534,13.221252679824829,-6.920256571651293,1744060581.4770558,13.221252679824829,-29.638579804355672,1744060581.4770586,13.221252679824829,0.0,1744060581.4770617,13.221252679824829,56568542496.923805,1744060581.477063,13.221252679824829,0.0,1744060581.4770644,13.221252679824829,5.239410190273439e-10,1744060581.477066,13.221252679824829,29.638579804355675,1744060581.4770675,13.221252679824829,4.267955490481195e-20,1744060581.4770691,13.221252679824829,10,1744060581.47707,13.221252679824829,0.0,1744060581.4770713,13.221252679824829,-22627416989.969524,1744060581.4770727,13.221252679824829,0.0,1744060581.477074,13.221252679824829,28284271247.461903
+1744060581.4977615,13.241345643997192,-6.920256571651293,1744060581.4977663,13.241345643997192,-29.638579804355672,1744060581.4977698,13.241345643997192,0.0,1744060581.4977744,13.241345643997192,56568542496.923805,1744060581.497776,13.241345643997192,0.0,1744060581.4977794,13.241345643997192,5.239410190273439e-10,1744060581.4977825,13.241345643997192,29.638579804355675,1744060581.497785,13.241345643997192,4.267955490481195e-20,1744060581.4977877,13.241345643997192,10,1744060581.4977899,13.241345643997192,0.0,1744060581.4977918,13.241345643997192,-22627416989.969524,1744060581.4977942,13.241345643997192,0.0,1744060581.4977977,13.241345643997192,28284271247.461903
+1744060581.5170693,13.261266231536865,-6.920256571651293,1744060581.5170717,13.261266231536865,-29.638579804355672,1744060581.517074,13.261266231536865,0.0,1744060581.517077,13.261266231536865,56568542496.923805,1744060581.5170782,13.261266231536865,0.0,1744060581.5170798,13.261266231536865,5.239410190273439e-10,1744060581.5170813,13.261266231536865,29.638579804355675,1744060581.517083,13.261266231536865,4.267955490481195e-20,1744060581.5170841,13.261266231536865,10,1744060581.517086,13.261266231536865,0.0,1744060581.5170872,13.261266231536865,-22627416989.969524,1744060581.5170884,13.261266231536865,0.0,1744060581.5170898,13.261266231536865,28284271247.461903
+1744060581.5370915,13.2812659740448,-6.920256571651293,1744060581.537094,13.2812659740448,-29.638579804355672,1744060581.537097,13.2812659740448,0.0,1744060581.5370998,13.2812659740448,56568542496.923805,1744060581.537101,13.2812659740448,0.0,1744060581.5371027,13.2812659740448,5.239410190273439e-10,1744060581.5371041,13.2812659740448,29.638579804355675,1744060581.5371056,13.2812659740448,4.267955490481195e-20,1744060581.5371072,13.2812659740448,10,1744060581.5371084,13.2812659740448,0.0,1744060581.5371099,13.2812659740448,-22627416989.969524,1744060581.537111,13.2812659740448,0.0,1744060581.5371122,13.2812659740448,28284271247.461903
+1744060581.5574844,13.30126166343689,-6.920256571651293,1744060581.5574865,13.30126166343689,-29.638579804355672,1744060581.5574892,13.30126166343689,0.0,1744060581.5574923,13.30126166343689,56568542496.923805,1744060581.5574934,13.30126166343689,0.0,1744060581.557495,13.30126166343689,5.239410190273439e-10,1744060581.5574968,13.30126166343689,29.638579804355675,1744060581.5574985,13.30126166343689,4.267955490481195e-20,1744060581.5574996,13.30126166343689,10,1744060581.557501,13.30126166343689,0.0,1744060581.5575025,13.30126166343689,-22627416989.969524,1744060581.5575035,13.30126166343689,0.0,1744060581.5575047,13.30126166343689,28284271247.461903
+1744060581.5770695,13.321254253387451,-6.920256571651293,1744060581.577072,13.321254253387451,-29.638579804355672,1744060581.5770745,13.321254253387451,0.0,1744060581.5770779,13.321254253387451,56568542496.923805,1744060581.577079,13.321254253387451,0.0,1744060581.5770805,13.321254253387451,5.239410190273439e-10,1744060581.5770822,13.321254253387451,29.638579804355675,1744060581.5770836,13.321254253387451,4.267955490481195e-20,1744060581.5770853,13.321254253387451,10,1744060581.5770864,13.321254253387451,0.0,1744060581.5770876,13.321254253387451,-22627416989.969524,1744060581.577089,13.321254253387451,0.0,1744060581.5770903,13.321254253387451,28284271247.461903
+1744060581.597099,13.341230869293213,-6.920256571651293,1744060581.5971012,13.341230869293213,-29.638579804355672,1744060581.597104,13.341230869293213,0.0,1744060581.597107,13.341230869293213,56568542496.923805,1744060581.5971081,13.341230869293213,0.0,1744060581.5971096,13.341230869293213,5.239410190273439e-10,1744060581.597111,13.341230869293213,29.638579804355675,1744060581.5971127,13.341230869293213,4.267955490481195e-20,1744060581.597114,13.341230869293213,10,1744060581.5971153,13.341230869293213,0.0,1744060581.5971167,13.341230869293213,-22627416989.969524,1744060581.597118,13.341230869293213,0.0,1744060581.5971196,13.341230869293213,28284271247.461903
+1744060581.6170642,13.361262559890747,-6.920256571651293,1744060581.6170669,13.361262559890747,-29.638579804355672,1744060581.6170695,13.361262559890747,0.0,1744060581.6170723,13.361262559890747,56568542496.923805,1744060581.6170738,13.361262559890747,0.0,1744060581.6170752,13.361262559890747,5.239410190273439e-10,1744060581.6170766,13.361262559890747,29.638579804355675,1744060581.6170783,13.361262559890747,4.267955490481195e-20,1744060581.6170795,13.361262559890747,10,1744060581.6170812,13.361262559890747,0.0,1744060581.6170824,13.361262559890747,-22627416989.969524,1744060581.6170835,13.361262559890747,0.0,1744060581.617085,13.361262559890747,28284271247.461903
+1744060581.637062,13.381261587142944,-6.920256571651293,1744060581.6370645,13.381261587142944,-29.638579804355672,1744060581.6370673,13.381261587142944,0.0,1744060581.6370702,13.381261587142944,56568542496.923805,1744060581.6370714,13.381261587142944,0.0,1744060581.6370728,13.381261587142944,5.239410190273439e-10,1744060581.6370745,13.381261587142944,29.638579804355675,1744060581.637076,13.381261587142944,4.267955490481195e-20,1744060581.6370776,13.381261587142944,10,1744060581.6370785,13.381261587142944,0.0,1744060581.6370797,13.381261587142944,-22627416989.969524,1744060581.6370811,13.381261587142944,0.0,1744060581.6370823,13.381261587142944,28284271247.461903
+1744060581.6574454,13.40123176574707,-6.920256571651293,1744060581.6574476,13.40123176574707,-29.638579804355672,1744060581.6574502,13.40123176574707,0.0,1744060581.6574533,13.40123176574707,56568542496.923805,1744060581.6574545,13.40123176574707,0.0,1744060581.6574562,13.40123176574707,5.239410190273439e-10,1744060581.6574576,13.40123176574707,29.638579804355675,1744060581.6574593,13.40123176574707,4.267955490481195e-20,1744060581.6574605,13.40123176574707,10,1744060581.6574616,13.40123176574707,0.0,1744060581.6574633,13.40123176574707,-22627416989.969524,1744060581.6574645,13.40123176574707,0.0,1744060581.657466,13.40123176574707,28284271247.461903
+1744060581.6770198,13.421252489089966,-6.920256571651293,1744060581.6770225,13.421252489089966,-29.638579804355672,1744060581.6770253,13.421252489089966,0.0,1744060581.6770282,13.421252489089966,56568542496.923805,1744060581.6770294,13.421252489089966,0.0,1744060581.6770308,13.421252489089966,5.239410190273439e-10,1744060581.6770325,13.421252489089966,29.638579804355675,1744060581.677034,13.421252489089966,4.267955490481195e-20,1744060581.6770353,13.421252489089966,10,1744060581.6770365,13.421252489089966,0.0,1744060581.6770377,13.421252489089966,-22627416989.969524,1744060581.6770391,13.421252489089966,0.0,1744060581.6770403,13.421252489089966,28284271247.461903
+1744060581.6971438,13.441248655319214,-6.920256571651293,1744060581.6971462,13.441248655319214,-29.638579804355672,1744060581.697149,13.441248655319214,0.0,1744060581.6971517,13.441248655319214,56568542496.923805,1744060581.6971533,13.441248655319214,0.0,1744060581.6971548,13.441248655319214,5.239410190273439e-10,1744060581.6971567,13.441248655319214,29.638579804355675,1744060581.6971579,13.441248655319214,4.267955490481195e-20,1744060581.6971595,13.441248655319214,10,1744060581.6971607,13.441248655319214,0.0,1744060581.697162,13.441248655319214,-22627416989.969524,1744060581.6971633,13.441248655319214,0.0,1744060581.6971645,13.441248655319214,28284271247.461903
+1744060581.7172356,13.461239337921143,-6.920256571651293,1744060581.7172377,13.461239337921143,-29.638579804355672,1744060581.7172408,13.461239337921143,0.0,1744060581.7172437,13.461239337921143,56568542496.923805,1744060581.7172449,13.461239337921143,0.0,1744060581.7172468,13.461239337921143,5.239410190273439e-10,1744060581.7172482,13.461239337921143,29.638579804355675,1744060581.7172499,13.461239337921143,4.267955490481195e-20,1744060581.7172513,13.461239337921143,10,1744060581.7172525,13.461239337921143,0.0,1744060581.717254,13.461239337921143,-22627416989.969524,1744060581.717255,13.461239337921143,0.0,1744060581.7172565,13.461239337921143,28284271247.461903
+1744060581.7370694,13.481262922286987,-6.920256571651293,1744060581.7370715,13.481262922286987,-29.638579804355672,1744060581.7370746,13.481262922286987,0.0,1744060581.7370775,13.481262922286987,56568542496.923805,1744060581.7370787,13.481262922286987,0.0,1744060581.7370803,13.481262922286987,5.239410190273439e-10,1744060581.7370818,13.481262922286987,29.638579804355675,1744060581.7370834,13.481262922286987,4.267955490481195e-20,1744060581.7370849,13.481262922286987,10,1744060581.7370863,13.481262922286987,0.0,1744060581.7370875,13.481262922286987,-22627416989.969524,1744060581.7370887,13.481262922286987,0.0,1744060581.73709,13.481262922286987,28284271247.461903
+1744060581.7577932,13.501245260238647,-7.148754602636156,1744060581.7577965,13.501245260238647,-30.732802302862506,1744060581.7578008,13.501245260238647,0.0,1744060581.757805,13.501245260238647,56568542496.923805,1744060581.7578073,13.501245260238647,0.0,1744060581.75781,13.501245260238647,5.432843227426258e-10,1744060581.757813,13.501245260238647,30.732802302862503,1744060581.7578156,13.501245260238647,4.425523530180732e-20,1744060581.7578182,13.501245260238647,10,1744060581.7578206,13.501245260238647,0.0,1744060581.757823,13.501245260238647,-22627416989.969524,1744060581.7578254,13.501245260238647,0.0,1744060581.7578278,13.501245260238647,28284271247.461903
+1744060581.7773914,13.521231174468994,-7.148754602636156,1744060581.7773952,13.521231174468994,-30.732802302862506,1744060581.7773993,13.521231174468994,0.0,1744060581.7774036,13.521231174468994,56568542496.923805,1744060581.7774062,13.521231174468994,0.0,1744060581.777409,13.521231174468994,5.432843227426258e-10,1744060581.7774117,13.521231174468994,30.732802302862503,1744060581.777414,13.521231174468994,4.425523530180732e-20,1744060581.7774167,13.521231174468994,10,1744060581.777419,13.521231174468994,0.0,1744060581.7774215,13.521231174468994,-22627416989.969524,1744060581.7774239,13.521231174468994,0.0,1744060581.7774265,13.521231174468994,28284271247.461903
+1744060581.7976902,13.541264295578003,-7.148754602636156,1744060581.7976933,13.541264295578003,-30.732802302862506,1744060581.7976956,13.541264295578003,0.0,1744060581.7976985,13.541264295578003,56568542496.923805,1744060581.7977002,13.541264295578003,0.0,1744060581.7977016,13.541264295578003,5.432843227426258e-10,1744060581.7977037,13.541264295578003,30.732802302862503,1744060581.7977052,13.541264295578003,4.425523530180732e-20,1744060581.7977068,13.541264295578003,10,1744060581.7977085,13.541264295578003,0.0,1744060581.79771,13.541264295578003,-22627416989.969524,1744060581.7977111,13.541264295578003,0.0,1744060581.7977123,13.541264295578003,28284271247.461903
+1744060581.817163,13.561247110366821,-7.148754602636156,1744060581.8171663,13.561247110366821,-30.732802302862506,1744060581.8171701,13.561247110366821,0.0,1744060581.817174,13.561247110366821,56568542496.923805,1744060581.8171759,13.561247110366821,0.0,1744060581.817178,13.561247110366821,5.432843227426258e-10,1744060581.8171804,13.561247110366821,30.732802302862503,1744060581.8171825,13.561247110366821,4.425523530180732e-20,1744060581.8171847,13.561247110366821,10,1744060581.8171868,13.561247110366821,0.0,1744060581.8171885,13.561247110366821,-22627416989.969524,1744060581.8171906,13.561247110366821,0.0,1744060581.8171928,13.561247110366821,28284271247.461903
+1744060581.837024,13.581229209899902,-7.148754602636156,1744060581.8370264,13.581229209899902,-30.732802302862506,1744060581.8370292,13.581229209899902,0.0,1744060581.8370316,13.581229209899902,56568542496.923805,1744060581.837033,13.581229209899902,0.0,1744060581.8370345,13.581229209899902,5.432843227426258e-10,1744060581.8370361,13.581229209899902,30.732802302862503,1744060581.8370376,13.581229209899902,4.425523530180732e-20,1744060581.837039,13.581229209899902,10,1744060581.8370404,13.581229209899902,0.0,1744060581.8370416,13.581229209899902,-22627416989.969524,1744060581.837043,13.581229209899902,0.0,1744060581.8370442,13.581229209899902,28284271247.461903
+1744060581.8576715,13.601261138916016,-7.148754602636156,1744060581.8576748,13.601261138916016,-30.732802302862506,1744060581.857678,13.601261138916016,0.0,1744060581.8576815,13.601261138916016,56568542496.923805,1744060581.857683,13.601261138916016,0.0,1744060581.8576853,13.601261138916016,5.432843227426258e-10,1744060581.8576875,13.601261138916016,30.732802302862503,1744060581.8576896,13.601261138916016,4.425523530180732e-20,1744060581.8576918,13.601261138916016,10,1744060581.8576932,13.601261138916016,0.0,1744060581.8576944,13.601261138916016,-22627416989.969524,1744060581.8576965,13.601261138916016,0.0,1744060581.8576977,13.601261138916016,28284271247.461903
+1744060581.8769875,13.621219873428345,-7.148754602636156,1744060581.8769896,13.621219873428345,-30.732802302862506,1744060581.8769925,13.621219873428345,0.0,1744060581.8769953,13.621219873428345,56568542496.923805,1744060581.8769965,13.621219873428345,0.0,1744060581.8769982,13.621219873428345,5.432843227426258e-10,1744060581.8769996,13.621219873428345,30.732802302862503,1744060581.8770013,13.621219873428345,4.425523530180732e-20,1744060581.8770027,13.621219873428345,10,1744060581.8770044,13.621219873428345,0.0,1744060581.8770053,13.621219873428345,-22627416989.969524,1744060581.8770065,13.621219873428345,0.0,1744060581.877008,13.621219873428345,28284271247.461903
+1744060581.897039,13.641253471374512,-7.148754602636156,1744060581.897041,13.641253471374512,-30.732802302862506,1744060581.897044,13.641253471374512,0.0,1744060581.897047,13.641253471374512,56568542496.923805,1744060581.8970482,13.641253471374512,0.0,1744060581.89705,13.641253471374512,5.432843227426258e-10,1744060581.8970513,13.641253471374512,30.732802302862503,1744060581.8970528,13.641253471374512,4.425523530180732e-20,1744060581.8970542,13.641253471374512,10,1744060581.8970554,13.641253471374512,0.0,1744060581.8970568,13.641253471374512,-22627416989.969524,1744060581.897058,13.641253471374512,0.0,1744060581.8970594,13.641253471374512,28284271247.461903
+1744060581.9171572,13.661255836486816,-7.148754602636156,1744060581.9171598,13.661255836486816,-30.732802302862506,1744060581.9171624,13.661255836486816,0.0,1744060581.917165,13.661255836486816,56568542496.923805,1744060581.9171662,13.661255836486816,0.0,1744060581.9171681,13.661255836486816,5.432843227426258e-10,1744060581.9171696,13.661255836486816,30.732802302862503,1744060581.9171712,13.661255836486816,4.425523530180732e-20,1744060581.9171727,13.661255836486816,10,1744060581.917174,13.661255836486816,0.0,1744060581.9171753,13.661255836486816,-22627416989.969524,1744060581.9171765,13.661255836486816,0.0,1744060581.917178,13.661255836486816,28284271247.461903
+1744060581.9370942,13.681259632110596,-7.148754602636156,1744060581.9370978,13.681259632110596,-30.732802302862506,1744060581.937102,13.681259632110596,0.0,1744060581.9371054,13.681259632110596,56568542496.923805,1744060581.9371078,13.681259632110596,0.0,1744060581.93711,13.681259632110596,5.432843227426258e-10,1744060581.937122,13.681259632110596,30.732802302862503,1744060581.9371266,13.681259632110596,4.425523530180732e-20,1744060581.937129,13.681259632110596,10,1744060581.9371307,13.681259632110596,0.0,1744060581.9371326,13.681259632110596,-22627416989.969524,1744060581.9371345,13.681259632110596,0.0,1744060581.9371364,13.681259632110596,28284271247.461903
+1744060581.9576476,13.7012939453125,-7.148754602636156,1744060581.9576504,13.7012939453125,-30.732802302862506,1744060581.9576535,13.7012939453125,0.0,1744060581.9576569,13.7012939453125,56568542496.923805,1744060581.9576583,13.7012939453125,0.0,1744060581.9576602,13.7012939453125,5.432843227426258e-10,1744060581.9576619,13.7012939453125,30.732802302862503,1744060581.9576633,13.7012939453125,4.425523530180732e-20,1744060581.957665,13.7012939453125,10,1744060581.9576664,13.7012939453125,0.0,1744060581.957668,13.7012939453125,-22627416989.969524,1744060581.95767,13.7012939453125,0.0,1744060581.9576714,13.7012939453125,28284271247.461903
+1744060581.9770038,13.721250772476196,-7.148754602636156,1744060581.9770062,13.721250772476196,-30.732802302862506,1744060581.9770088,13.721250772476196,0.0,1744060581.9770117,13.721250772476196,56568542496.923805,1744060581.9770133,13.721250772476196,0.0,1744060581.977015,13.721250772476196,5.432843227426258e-10,1744060581.9770167,13.721250772476196,30.732802302862503,1744060581.977018,13.721250772476196,4.425523530180732e-20,1744060581.9770195,13.721250772476196,10,1744060581.977021,13.721250772476196,0.0,1744060581.9770224,13.721250772476196,-22627416989.969524,1744060581.977024,13.721250772476196,0.0,1744060581.9770253,13.721250772476196,28284271247.461903
+1744060581.9971957,13.74123764038086,-7.148754602636156,1744060581.9971986,13.74123764038086,-30.732802302862506,1744060581.9972014,13.74123764038086,0.0,1744060581.9972053,13.74123764038086,56568542496.923805,1744060581.9972067,13.74123764038086,0.0,1744060581.9972088,13.74123764038086,5.432843227426258e-10,1744060581.9972107,13.74123764038086,30.732802302862503,1744060581.9972122,13.74123764038086,4.425523530180732e-20,1744060581.997215,13.74123764038086,10,1744060581.9972165,13.74123764038086,0.0,1744060581.997218,13.74123764038086,-22627416989.969524,1744060581.9972193,13.74123764038086,0.0,1744060581.9972208,13.74123764038086,28284271247.461903
+1744060582.0170197,13.761250734329224,-7.148754602636156,1744060582.0170217,13.761250734329224,-30.732802302862506,1744060582.0170245,13.761250734329224,0.0,1744060582.0170274,13.761250734329224,56568542496.923805,1744060582.0170286,13.761250734329224,0.0,1744060582.0170305,13.761250734329224,5.432843227426258e-10,1744060582.017032,13.761250734329224,30.732802302862503,1744060582.017033,13.761250734329224,4.425523530180732e-20,1744060582.0170348,13.761250734329224,10,1744060582.017036,13.761250734329224,0.0,1744060582.0170374,13.761250734329224,-22627416989.969524,1744060582.0170386,13.761250734329224,0.0,1744060582.0170398,13.761250734329224,28284271247.461903
+1744060582.0370507,13.781256914138794,-7.148754602636156,1744060582.0370529,13.781256914138794,-30.732802302862506,1744060582.0370557,13.781256914138794,0.0,1744060582.0370584,13.781256914138794,56568542496.923805,1744060582.0370595,13.781256914138794,0.0,1744060582.0370612,13.781256914138794,5.432843227426258e-10,1744060582.0370626,13.781256914138794,30.732802302862503,1744060582.037064,13.781256914138794,4.425523530180732e-20,1744060582.0370655,13.781256914138794,10,1744060582.0370667,13.781256914138794,0.0,1744060582.0370681,13.781256914138794,-22627416989.969524,1744060582.0370693,13.781256914138794,0.0,1744060582.0370705,13.781256914138794,28284271247.461903
+1744060582.0574818,13.801243782043457,-7.148754602636156,1744060582.0574844,13.801243782043457,-30.732802302862506,1744060582.057487,13.801243782043457,0.0,1744060582.0574896,13.801243782043457,56568542496.923805,1744060582.0574908,13.801243782043457,0.0,1744060582.0574925,13.801243782043457,5.432843227426258e-10,1744060582.057494,13.801243782043457,30.732802302862503,1744060582.0574956,13.801243782043457,4.425523530180732e-20,1744060582.057497,13.801243782043457,10,1744060582.0574987,13.801243782043457,0.0,1744060582.0575,13.801243782043457,-22627416989.969524,1744060582.057501,13.801243782043457,0.0,1744060582.0575025,13.801243782043457,28284271247.461903
+1744060582.0770543,13.821262836456299,-7.148754602636156,1744060582.0770564,13.821262836456299,-30.732802302862506,1744060582.0770593,13.821262836456299,0.0,1744060582.0770621,13.821262836456299,56568542496.923805,1744060582.0770633,13.821262836456299,0.0,1744060582.077065,13.821262836456299,5.432843227426258e-10,1744060582.0770664,13.821262836456299,30.732802302862503,1744060582.077068,13.821262836456299,4.425523530180732e-20,1744060582.0770695,13.821262836456299,10,1744060582.0770712,13.821262836456299,0.0,1744060582.0770724,13.821262836456299,-22627416989.969524,1744060582.0770736,13.821262836456299,0.0,1744060582.077075,13.821262836456299,28284271247.461903
+1744060582.0973175,13.841240167617798,-7.148754602636156,1744060582.0973198,13.841240167617798,-30.732802302862506,1744060582.0973225,13.841240167617798,0.0,1744060582.0973253,13.841240167617798,56568542496.923805,1744060582.0973265,13.841240167617798,0.0,1744060582.0973284,13.841240167617798,5.432843227426258e-10,1744060582.09733,13.841240167617798,30.732802302862503,1744060582.0973318,13.841240167617798,4.425523530180732e-20,1744060582.097333,13.841240167617798,10,1744060582.0973344,13.841240167617798,0.0,1744060582.0973356,13.841240167617798,-22627416989.969524,1744060582.0973368,13.841240167617798,0.0,1744060582.0973382,13.841240167617798,28284271247.461903
+1744060582.117035,13.861259460449219,-7.148754602636156,1744060582.1170378,13.861259460449219,-30.732802302862506,1744060582.1170406,13.861259460449219,0.0,1744060582.1170437,13.861259460449219,56568542496.923805,1744060582.117045,13.861259460449219,0.0,1744060582.1170468,13.861259460449219,5.432843227426258e-10,1744060582.1170483,13.861259460449219,30.732802302862503,1744060582.11705,13.861259460449219,4.425523530180732e-20,1744060582.1170516,13.861259460449219,10,1744060582.1170526,13.861259460449219,0.0,1744060582.1170542,13.861259460449219,-22627416989.969524,1744060582.1170552,13.861259460449219,0.0,1744060582.1170568,13.861259460449219,28284271247.461903
+1744060582.1370933,13.881253719329834,-7.148754602636156,1744060582.1370962,13.881253719329834,-30.732802302862506,1744060582.137099,13.881253719329834,0.0,1744060582.137102,13.881253719329834,56568542496.923805,1744060582.137103,13.881253719329834,0.0,1744060582.1371047,13.881253719329834,5.432843227426258e-10,1744060582.1371062,13.881253719329834,30.732802302862503,1744060582.1371074,13.881253719329834,4.425523530180732e-20,1744060582.137109,13.881253719329834,10,1744060582.1371102,13.881253719329834,0.0,1744060582.1371117,13.881253719329834,-22627416989.969524,1744060582.1371129,13.881253719329834,0.0,1744060582.1371143,13.881253719329834,28284271247.461903
+1744060582.1579335,13.901253700256348,-7.148754602636156,1744060582.1579366,13.901253700256348,-30.732802302862506,1744060582.1579394,13.901253700256348,0.0,1744060582.157942,13.901253700256348,56568542496.923805,1744060582.1579432,13.901253700256348,0.0,1744060582.1579452,13.901253700256348,5.432843227426258e-10,1744060582.157947,13.901253700256348,30.732802302862503,1744060582.157949,13.901253700256348,4.425523530180732e-20,1744060582.1579509,13.901253700256348,10,1744060582.1579525,13.901253700256348,0.0,1744060582.1579537,13.901253700256348,-22627416989.969524,1744060582.1579554,13.901253700256348,0.0,1744060582.157957,13.901253700256348,28284271247.461903
+1744060582.1770594,13.921252965927124,-7.148754602636156,1744060582.1770618,13.921252965927124,-30.732802302862506,1744060582.1770647,13.921252965927124,0.0,1744060582.1770675,13.921252965927124,56568542496.923805,1744060582.1770687,13.921252965927124,0.0,1744060582.1770706,13.921252965927124,5.432843227426258e-10,1744060582.177072,13.921252965927124,30.732802302862503,1744060582.177074,13.921252965927124,4.425523530180732e-20,1744060582.1770751,13.921252965927124,10,1744060582.1770768,13.921252965927124,0.0,1744060582.177078,13.921252965927124,-22627416989.969524,1744060582.1770792,13.921252965927124,0.0,1744060582.1770806,13.921252965927124,28284271247.461903
+1744060582.1971872,13.941280841827393,-7.148754602636156,1744060582.1971896,13.941280841827393,-30.732802302862506,1744060582.1971931,13.941280841827393,0.0,1744060582.197196,13.941280841827393,56568542496.923805,1744060582.1971972,13.941280841827393,0.0,1744060582.1971989,13.941280841827393,5.432843227426258e-10,1744060582.1972003,13.941280841827393,30.732802302862503,1744060582.197202,13.941280841827393,4.425523530180732e-20,1744060582.1972036,13.941280841827393,10,1744060582.197205,13.941280841827393,0.0,1744060582.1972063,13.941280841827393,-22627416989.969524,1744060582.1972075,13.941280841827393,0.0,1744060582.197209,13.941280841827393,28284271247.461903
+1744060582.2170606,13.961263656616211,-7.148754602636156,1744060582.2170632,13.961263656616211,-30.732802302862506,1744060582.217066,13.961263656616211,0.0,1744060582.217069,13.961263656616211,56568542496.923805,1744060582.2170703,13.961263656616211,0.0,1744060582.2170718,13.961263656616211,5.432843227426258e-10,1744060582.2170734,13.961263656616211,30.732802302862503,1744060582.2170749,13.961263656616211,4.425523530180732e-20,1744060582.2170765,13.961263656616211,10,1744060582.2170775,13.961263656616211,0.0,1744060582.217079,13.961263656616211,-22627416989.969524,1744060582.2170804,13.961263656616211,0.0,1744060582.2170815,13.961263656616211,28284271247.461903
+1744060582.237086,13.981231212615967,-7.148754602636156,1744060582.2370894,13.981231212615967,-30.732802302862506,1744060582.237093,13.981231212615967,0.0,1744060582.2370956,13.981231212615967,56568542496.923805,1744060582.2370973,13.981231212615967,0.0,1744060582.237099,13.981231212615967,5.432843227426258e-10,1744060582.2371008,13.981231212615967,30.732802302862503,1744060582.2371025,13.981231212615967,4.425523530180732e-20,1744060582.2371047,13.981231212615967,10,1744060582.2371073,13.981231212615967,0.0,1744060582.2371092,13.981231212615967,-22627416989.969524,1744060582.2371113,13.981231212615967,0.0,1744060582.2371128,13.981231212615967,28284271247.461903
+1744060582.257434,14.001268863677979,-7.213153684024327,1744060582.2574363,14.001268863677979,-31.46698256281315,1744060582.257439,14.001268863677979,0.0,1744060582.2574418,14.001268863677979,56568542496.923805,1744060582.2574432,14.001268863677979,0.0,1744060582.2574446,14.001268863677979,5.562629187505038e-10,1744060582.257446,14.001268863677979,31.466982562813154,1744060582.2574477,14.001268863677979,4.531245487569113e-20,1744060582.2574492,14.001268863677979,10,1744060582.2574506,14.001268863677979,0.0,1744060582.2574515,14.001268863677979,-22627416989.969524,1744060582.2574527,14.001268863677979,0.0,1744060582.2574542,14.001268863677979,28284271247.461903
+1744060582.2770386,14.021225929260254,-7.213153684024327,1744060582.277041,14.021225929260254,-31.46698256281315,1744060582.2770433,14.021225929260254,0.0,1744060582.2770462,14.021225929260254,56568542496.923805,1744060582.2770476,14.021225929260254,0.0,1744060582.277049,14.021225929260254,5.562629187505038e-10,1744060582.2770507,14.021225929260254,31.466982562813154,1744060582.2770524,14.021225929260254,4.531245487569113e-20,1744060582.2770536,14.021225929260254,10,1744060582.2770553,14.021225929260254,0.0,1744060582.2770565,14.021225929260254,-22627416989.969524,1744060582.277058,14.021225929260254,0.0,1744060582.2770593,14.021225929260254,28284271247.461903
+1744060582.2971783,14.04127287864685,-7.213153684024327,1744060582.2971804,14.04127287864685,-31.46698256281315,1744060582.2971828,14.04127287864685,0.0,1744060582.2971852,14.04127287864685,56568542496.923805,1744060582.2971866,14.04127287864685,0.0,1744060582.2971878,14.04127287864685,5.562629187505038e-10,1744060582.2971897,14.04127287864685,31.466982562813154,1744060582.297191,14.04127287864685,4.531245487569113e-20,1744060582.297192,14.04127287864685,10,1744060582.2971935,14.04127287864685,0.0,1744060582.2971945,14.04127287864685,-22627416989.969524,1744060582.2971957,14.04127287864685,0.0,1744060582.2971969,14.04127287864685,28284271247.461903
+1744060582.3168983,14.061225414276123,-7.213153684024327,1744060582.3169,14.061225414276123,-31.46698256281315,1744060582.3169022,14.061225414276123,0.0,1744060582.3169045,14.061225414276123,56568542496.923805,1744060582.3169055,14.061225414276123,0.0,1744060582.3169065,14.061225414276123,5.562629187505038e-10,1744060582.316908,14.061225414276123,31.466982562813154,1744060582.316909,14.061225414276123,4.531245487569113e-20,1744060582.31691,14.061225414276123,10,1744060582.3169112,14.061225414276123,0.0,1744060582.316912,14.061225414276123,-22627416989.969524,1744060582.316913,14.061225414276123,0.0,1744060582.3169138,14.061225414276123,28284271247.461903
+1744060582.3369575,14.081259727478027,-7.213153684024327,1744060582.3369596,14.081259727478027,-31.46698256281315,1744060582.3369617,14.081259727478027,0.0,1744060582.336964,14.081259727478027,56568542496.923805,1744060582.3369648,14.081259727478027,0.0,1744060582.3369658,14.081259727478027,5.562629187505038e-10,1744060582.3369672,14.081259727478027,31.466982562813154,1744060582.3369682,14.081259727478027,4.531245487569113e-20,1744060582.3369694,14.081259727478027,10,1744060582.3369706,14.081259727478027,0.0,1744060582.3369715,14.081259727478027,-22627416989.969524,1744060582.3369722,14.081259727478027,0.0,1744060582.3369734,14.081259727478027,28284271247.461903
+1744060582.357446,14.101272344589233,-7.213153684024327,1744060582.3574476,14.101272344589233,-31.46698256281315,1744060582.35745,14.101272344589233,0.0,1744060582.357452,14.101272344589233,56568542496.923805,1744060582.357453,14.101272344589233,0.0,1744060582.357454,14.101272344589233,5.562629187505038e-10,1744060582.3574553,14.101272344589233,31.466982562813154,1744060582.3574564,14.101272344589233,4.531245487569113e-20,1744060582.3574574,14.101272344589233,10,1744060582.3574584,14.101272344589233,0.0,1744060582.3574595,14.101272344589233,-22627416989.969524,1744060582.3574605,14.101272344589233,0.0,1744060582.3574615,14.101272344589233,28284271247.461903
+1744060582.377307,14.121252059936523,-7.213153684024327,1744060582.3773086,14.121252059936523,-31.46698256281315,1744060582.3773108,14.121252059936523,0.0,1744060582.3773131,14.121252059936523,56568542496.923805,1744060582.3773139,14.121252059936523,0.0,1744060582.377315,14.121252059936523,5.562629187505038e-10,1744060582.377316,14.121252059936523,31.466982562813154,1744060582.3773174,14.121252059936523,4.531245487569113e-20,1744060582.3773184,14.121252059936523,10,1744060582.3773193,14.121252059936523,0.0,1744060582.3773205,14.121252059936523,-22627416989.969524,1744060582.3773212,14.121252059936523,0.0,1744060582.3773222,14.121252059936523,28284271247.461903
+1744060582.3970942,14.14123249053955,-7.213153684024327,1744060582.3970964,14.14123249053955,-31.46698256281315,1744060582.3970995,14.14123249053955,0.0,1744060582.3971038,14.14123249053955,56568542496.923805,1744060582.3971057,14.14123249053955,0.0,1744060582.3971076,14.14123249053955,5.562629187505038e-10,1744060582.3971097,14.14123249053955,31.466982562813154,1744060582.3971117,14.14123249053955,4.531245487569113e-20,1744060582.3971133,14.14123249053955,10,1744060582.3971145,14.14123249053955,0.0,1744060582.3971162,14.14123249053955,-22627416989.969524,1744060582.3971176,14.14123249053955,0.0,1744060582.3971198,14.14123249053955,28284271247.461903
+1744060582.4168692,14.161218643188477,-7.213153684024327,1744060582.4168708,14.161218643188477,-31.46698256281315,1744060582.4168732,14.161218643188477,0.0,1744060582.4168754,14.161218643188477,56568542496.923805,1744060582.4168763,14.161218643188477,0.0,1744060582.4168775,14.161218643188477,5.562629187505038e-10,1744060582.4168787,14.161218643188477,31.466982562813154,1744060582.41688,14.161218643188477,4.531245487569113e-20,1744060582.4168808,14.161218643188477,10,1744060582.416882,14.161218643188477,0.0,1744060582.4168828,14.161218643188477,-22627416989.969524,1744060582.4168837,14.161218643188477,0.0,1744060582.4168847,14.161218643188477,28284271247.461903
+1744060582.4369283,14.181224346160889,-7.213153684024327,1744060582.4369304,14.181224346160889,-31.46698256281315,1744060582.4369323,14.181224346160889,0.0,1744060582.4369345,14.181224346160889,56568542496.923805,1744060582.4369354,14.181224346160889,0.0,1744060582.4369364,14.181224346160889,5.562629187505038e-10,1744060582.4369376,14.181224346160889,31.466982562813154,1744060582.4369385,14.181224346160889,4.531245487569113e-20,1744060582.4369397,14.181224346160889,10,1744060582.436941,14.181224346160889,0.0,1744060582.4369419,14.181224346160889,-22627416989.969524,1744060582.4369428,14.181224346160889,0.0,1744060582.4369438,14.181224346160889,28284271247.461903
+1744060582.4576015,14.201286792755127,-7.213153684024327,1744060582.4576032,14.201286792755127,-31.46698256281315,1744060582.4576054,14.201286792755127,0.0,1744060582.457608,14.201286792755127,56568542496.923805,1744060582.457609,14.201286792755127,0.0,1744060582.4576101,14.201286792755127,5.562629187505038e-10,1744060582.4576116,14.201286792755127,31.466982562813154,1744060582.4576125,14.201286792755127,4.531245487569113e-20,1744060582.4576137,14.201286792755127,10,1744060582.457615,14.201286792755127,0.0,1744060582.4576159,14.201286792755127,-22627416989.969524,1744060582.4576168,14.201286792755127,0.0,1744060582.457618,14.201286792755127,28284271247.461903
+1744060582.4769533,14.221219539642334,-7.213153684024327,1744060582.4769552,14.221219539642334,-31.46698256281315,1744060582.476957,14.221219539642334,0.0,1744060582.4769592,14.221219539642334,56568542496.923805,1744060582.47696,14.221219539642334,0.0,1744060582.4769614,14.221219539642334,5.562629187505038e-10,1744060582.4769626,14.221219539642334,31.466982562813154,1744060582.4769635,14.221219539642334,4.531245487569113e-20,1744060582.476965,14.221219539642334,10,1744060582.476966,14.221219539642334,0.0,1744060582.4769669,14.221219539642334,-22627416989.969524,1744060582.476968,14.221219539642334,0.0,1744060582.4769688,14.221219539642334,28284271247.461903
+1744060582.4972115,14.241254568099976,-7.213153684024327,1744060582.4972136,14.241254568099976,-31.46698256281315,1744060582.497216,14.241254568099976,0.0,1744060582.4972363,14.241254568099976,56568542496.923805,1744060582.4972372,14.241254568099976,0.0,1744060582.4972389,14.241254568099976,5.562629187505038e-10,1744060582.49724,14.241254568099976,31.466982562813154,1744060582.497241,14.241254568099976,4.531245487569113e-20,1744060582.4972425,14.241254568099976,10,1744060582.4972668,14.241254568099976,0.0,1744060582.4972677,14.241254568099976,-22627416989.969524,1744060582.4972687,14.241254568099976,0.0,1744060582.4972699,14.241254568099976,28284271247.461903
+1744060582.5169015,14.261249780654907,-7.213153684024327,1744060582.5169032,14.261249780654907,-31.46698256281315,1744060582.5169053,14.261249780654907,0.0,1744060582.5169072,14.261249780654907,56568542496.923805,1744060582.5169082,14.261249780654907,0.0,1744060582.5169096,14.261249780654907,5.562629187505038e-10,1744060582.5169106,14.261249780654907,31.466982562813154,1744060582.5169122,14.261249780654907,4.531245487569113e-20,1744060582.5169132,14.261249780654907,10,1744060582.5169141,14.261249780654907,0.0,1744060582.5169148,14.261249780654907,-22627416989.969524,1744060582.516916,14.261249780654907,0.0,1744060582.516917,14.261249780654907,28284271247.461903
+1744060582.5370035,14.281231880187988,-7.213153684024327,1744060582.5370054,14.281231880187988,-31.46698256281315,1744060582.537008,14.281231880187988,0.0,1744060582.5370104,14.281231880187988,56568542496.923805,1744060582.5370114,14.281231880187988,0.0,1744060582.5370128,14.281231880187988,5.562629187505038e-10,1744060582.537014,14.281231880187988,31.466982562813154,1744060582.5370152,14.281231880187988,4.531245487569113e-20,1744060582.5370169,14.281231880187988,10,1744060582.5370178,14.281231880187988,0.0,1744060582.5370188,14.281231880187988,-22627416989.969524,1744060582.5370204,14.281231880187988,0.0,1744060582.5370214,14.281231880187988,28284271247.461903
+1744060582.5580091,14.301419734954834,-7.213153684024327,1744060582.5580113,14.301419734954834,-31.46698256281315,1744060582.5580144,14.301419734954834,0.0,1744060582.5580177,14.301419734954834,56568542496.923805,1744060582.5580199,14.301419734954834,0.0,1744060582.5580218,14.301419734954834,5.562629187505038e-10,1744060582.5580242,14.301419734954834,31.466982562813154,1744060582.5580263,14.301419734954834,4.531245487569113e-20,1744060582.5580475,14.301419734954834,10,1744060582.5580487,14.301419734954834,0.0,1744060582.5580502,14.301419734954834,-22627416989.969524,1744060582.5580513,14.301419734954834,0.0,1744060582.5580523,14.301419734954834,28284271247.461903
+1744060582.577301,14.321276664733887,-7.213153684024327,1744060582.577303,14.321276664733887,-31.46698256281315,1744060582.5773053,14.321276664733887,0.0,1744060582.5773077,14.321276664733887,56568542496.923805,1744060582.5773084,14.321276664733887,0.0,1744060582.5773096,14.321276664733887,5.562629187505038e-10,1744060582.5773108,14.321276664733887,31.466982562813154,1744060582.5773118,14.321276664733887,4.531245487569113e-20,1744060582.577313,14.321276664733887,10,1744060582.5773141,14.321276664733887,0.0,1744060582.5773153,14.321276664733887,-22627416989.969524,1744060582.5773165,14.321276664733887,0.0,1744060582.5773177,14.321276664733887,28284271247.461903
+1744060582.5974596,14.34128189086914,-7.213153684024327,1744060582.5974615,14.34128189086914,-31.46698256281315,1744060582.5974638,14.34128189086914,0.0,1744060582.5974662,14.34128189086914,56568542496.923805,1744060582.5974672,14.34128189086914,0.0,1744060582.5974686,14.34128189086914,5.562629187505038e-10,1744060582.5974698,14.34128189086914,31.466982562813154,1744060582.5974708,14.34128189086914,4.531245487569113e-20,1744060582.597472,14.34128189086914,10,1744060582.597473,14.34128189086914,0.0,1744060582.597474,14.34128189086914,-22627416989.969524,1744060582.5974748,14.34128189086914,0.0,1744060582.5974758,14.34128189086914,28284271247.461903
+1744060582.6169457,14.36124873161316,-7.213153684024327,1744060582.6169472,14.36124873161316,-31.46698256281315,1744060582.6169496,14.36124873161316,0.0,1744060582.6169515,14.36124873161316,56568542496.923805,1744060582.6169527,14.36124873161316,0.0,1744060582.6169538,14.36124873161316,5.562629187505038e-10,1744060582.616955,14.36124873161316,31.466982562813154,1744060582.6169565,14.36124873161316,4.531245487569113e-20,1744060582.6169574,14.36124873161316,10,1744060582.6169584,14.36124873161316,0.0,1744060582.6169593,14.36124873161316,-22627416989.969524,1744060582.6169603,14.36124873161316,0.0,1744060582.6169612,14.36124873161316,28284271247.461903
+1744060582.6374245,14.381297826766968,-7.213153684024327,1744060582.6374283,14.381297826766968,-31.46698256281315,1744060582.6374304,14.381297826766968,0.0,1744060582.6374333,14.381297826766968,56568542496.923805,1744060582.6374345,14.381297826766968,0.0,1744060582.637436,14.381297826766968,5.562629187505038e-10,1744060582.6374373,14.381297826766968,31.466982562813154,1744060582.637439,14.381297826766968,4.531245487569113e-20,1744060582.6374407,14.381297826766968,10,1744060582.637442,14.381297826766968,0.0,1744060582.6374433,14.381297826766968,-22627416989.969524,1744060582.6374454,14.381297826766968,0.0,1744060582.6374466,14.381297826766968,28284271247.461903
+1744060582.657245,14.401252269744873,-7.213153684024327,1744060582.6572473,14.401252269744873,-31.46698256281315,1744060582.6572495,14.401252269744873,0.0,1744060582.6572516,14.401252269744873,56568542496.923805,1744060582.6572526,14.401252269744873,0.0,1744060582.6572542,14.401252269744873,5.562629187505038e-10,1744060582.6572552,14.401252269744873,31.466982562813154,1744060582.6572564,14.401252269744873,4.531245487569113e-20,1744060582.657258,14.401252269744873,10,1744060582.6572592,14.401252269744873,0.0,1744060582.657261,14.401252269744873,-22627416989.969524,1744060582.6572623,14.401252269744873,0.0,1744060582.6572638,14.401252269744873,28284271247.461903
+1744060582.6769085,14.421247243881226,-7.213153684024327,1744060582.6769104,14.421247243881226,-31.46698256281315,1744060582.6769123,14.421247243881226,0.0,1744060582.6769145,14.421247243881226,56568542496.923805,1744060582.6769152,14.421247243881226,0.0,1744060582.6769164,14.421247243881226,5.562629187505038e-10,1744060582.6769178,14.421247243881226,31.466982562813154,1744060582.6769187,14.421247243881226,4.531245487569113e-20,1744060582.6769202,14.421247243881226,10,1744060582.6769211,14.421247243881226,0.0,1744060582.676922,14.421247243881226,-22627416989.969524,1744060582.6769228,14.421247243881226,0.0,1744060582.676924,14.421247243881226,28284271247.461903
+1744060582.6969283,14.441250801086426,-7.213153684024327,1744060582.69693,14.441250801086426,-31.46698256281315,1744060582.696932,14.441250801086426,0.0,1744060582.6969342,14.441250801086426,56568542496.923805,1744060582.696935,14.441250801086426,0.0,1744060582.6969361,14.441250801086426,5.562629187505038e-10,1744060582.6969373,14.441250801086426,31.466982562813154,1744060582.6969383,14.441250801086426,4.531245487569113e-20,1744060582.6969392,14.441250801086426,10,1744060582.6969402,14.441250801086426,0.0,1744060582.6969414,14.441250801086426,-22627416989.969524,1744060582.6969423,14.441250801086426,0.0,1744060582.6969433,14.441250801086426,28284271247.461903
+1744060582.7172568,14.461307764053345,-7.213153684024327,1744060582.7172592,14.461307764053345,-31.46698256281315,1744060582.7172623,14.461307764053345,0.0,1744060582.7172654,14.461307764053345,56568542496.923805,1744060582.717267,14.461307764053345,0.0,1744060582.7172692,14.461307764053345,5.562629187505038e-10,1744060582.7172713,14.461307764053345,31.466982562813154,1744060582.7172723,14.461307764053345,4.531245487569113e-20,1744060582.7172737,14.461307764053345,10,1744060582.717275,14.461307764053345,0.0,1744060582.7172759,14.461307764053345,-22627416989.969524,1744060582.7172766,14.461307764053345,0.0,1744060582.7172778,14.461307764053345,28284271247.461903
+1744060582.7369714,14.481258630752563,-7.213153684024327,1744060582.736973,14.481258630752563,-31.46698256281315,1744060582.7369752,14.481258630752563,0.0,1744060582.7369773,14.481258630752563,56568542496.923805,1744060582.7369785,14.481258630752563,0.0,1744060582.7369797,14.481258630752563,5.562629187505038e-10,1744060582.736981,14.481258630752563,31.466982562813154,1744060582.736982,14.481258630752563,4.531245487569113e-20,1744060582.736983,14.481258630752563,10,1744060582.736984,14.481258630752563,0.0,1744060582.7369854,14.481258630752563,-22627416989.969524,1744060582.7369864,14.481258630752563,0.0,1744060582.736987,14.481258630752563,28284271247.461903
+1744060582.75728,14.501260757446289,-7.324209430571672,1744060582.7572818,14.501260757446289,-31.83059407567148,1744060582.7572837,14.501260757446289,0.0,1744060582.7572856,14.501260757446289,56568542496.923805,1744060582.7572865,14.501260757446289,0.0,1744060582.757288,14.501260757446289,5.626907229098427e-10,1744060582.7572892,14.501260757446289,31.830594075671478,1744060582.7572901,14.501260757446289,4.583605545385658e-20,1744060582.7572913,14.501260757446289,10,1744060582.7572923,14.501260757446289,0.0,1744060582.7572932,14.501260757446289,-22627416989.969524,1744060582.7572944,14.501260757446289,0.0,1744060582.7572951,14.501260757446289,28284271247.461903
+1744060582.7775362,14.521220684051514,-7.324209430571672,1744060582.777538,14.521220684051514,-31.83059407567148,1744060582.7775404,14.521220684051514,0.0,1744060582.7775426,14.521220684051514,56568542496.923805,1744060582.7775438,14.521220684051514,0.0,1744060582.777545,14.521220684051514,5.626907229098427e-10,1744060582.7775462,14.521220684051514,31.830594075671478,1744060582.7775474,14.521220684051514,4.583605545385658e-20,1744060582.7775488,14.521220684051514,10,1744060582.7775497,14.521220684051514,0.0,1744060582.777551,14.521220684051514,-22627416989.969524,1744060582.777552,14.521220684051514,0.0,1744060582.777553,14.521220684051514,28284271247.461903
+1744060582.797647,14.54126524925232,-7.324209430571672,1744060582.79765,14.54126524925232,-31.83059407567148,1744060582.7976532,14.54126524925232,0.0,1744060582.7976568,14.54126524925232,56568542496.923805,1744060582.7976584,14.54126524925232,0.0,1744060582.7976604,14.54126524925232,5.626907229098427e-10,1744060582.797662,14.54126524925232,31.830594075671478,1744060582.797664,14.54126524925232,4.583605545385658e-20,1744060582.7976656,14.54126524925232,10,1744060582.797667,14.54126524925232,0.0,1744060582.7976687,14.54126524925232,-22627416989.969524,1744060582.7976701,14.54126524925232,0.0,1744060582.7976718,14.54126524925232,28284271247.461903
+1744060582.8168979,14.561222553253174,-7.324209430571672,1744060582.8168998,14.561222553253174,-31.83059407567148,1744060582.816902,14.561222553253174,0.0,1744060582.8169038,14.561222553253174,56568542496.923805,1744060582.816905,14.561222553253174,0.0,1744060582.8169062,14.561222553253174,5.626907229098427e-10,1744060582.8169074,14.561222553253174,31.830594075671478,1744060582.8169086,14.561222553253174,4.583605545385658e-20,1744060582.8169096,14.561222553253174,10,1744060582.8169103,14.561222553253174,0.0,1744060582.8169115,14.561222553253174,-22627416989.969524,1744060582.8169124,14.561222553253174,0.0,1744060582.8169134,14.561222553253174,28284271247.461903
+1744060582.8369067,14.581248044967651,-7.324209430571672,1744060582.8369086,14.581248044967651,-31.83059407567148,1744060582.8369105,14.581248044967651,0.0,1744060582.8369126,14.581248044967651,56568542496.923805,1744060582.8369133,14.581248044967651,0.0,1744060582.8369148,14.581248044967651,5.626907229098427e-10,1744060582.8369157,14.581248044967651,31.830594075671478,1744060582.8369167,14.581248044967651,4.583605545385658e-20,1744060582.836918,14.581248044967651,10,1744060582.8369188,14.581248044967651,0.0,1744060582.8369198,14.581248044967651,-22627416989.969524,1744060582.836921,14.581248044967651,0.0,1744060582.836922,14.581248044967651,28284271247.461903
+1744060582.857761,14.601275205612183,-7.324209430571672,1744060582.857763,14.601275205612183,-31.83059407567148,1744060582.8577652,14.601275205612183,0.0,1744060582.8577673,14.601275205612183,56568542496.923805,1744060582.8577685,14.601275205612183,0.0,1744060582.8577697,14.601275205612183,5.626907229098427e-10,1744060582.8577707,14.601275205612183,31.830594075671478,1744060582.857772,14.601275205612183,4.583605545385658e-20,1744060582.8577733,14.601275205612183,10,1744060582.8577743,14.601275205612183,0.0,1744060582.8577754,14.601275205612183,-22627416989.969524,1744060582.8577769,14.601275205612183,0.0,1744060582.8577776,14.601275205612183,28284271247.461903
+1744060582.8769956,14.621272802352905,-7.324209430571672,1744060582.8769975,14.621272802352905,-31.83059407567148,1744060582.8769994,14.621272802352905,0.0,1744060582.8770015,14.621272802352905,56568542496.923805,1744060582.8770025,14.621272802352905,0.0,1744060582.8770037,14.621272802352905,5.626907229098427e-10,1744060582.8770049,14.621272802352905,31.830594075671478,1744060582.8770058,14.621272802352905,4.583605545385658e-20,1744060582.877007,14.621272802352905,10,1744060582.8770082,14.621272802352905,0.0,1744060582.877009,14.621272802352905,-22627416989.969524,1744060582.8770099,14.621272802352905,0.0,1744060582.877011,14.621272802352905,28284271247.461903
+1744060582.8970335,14.641289949417114,-7.324209430571672,1744060582.8970354,14.641289949417114,-31.83059407567148,1744060582.8970373,14.641289949417114,0.0,1744060582.8970397,14.641289949417114,56568542496.923805,1744060582.8970406,14.641289949417114,0.0,1744060582.8970416,14.641289949417114,5.626907229098427e-10,1744060582.897043,14.641289949417114,31.830594075671478,1744060582.897044,14.641289949417114,4.583605545385658e-20,1744060582.897045,14.641289949417114,10,1744060582.897046,14.641289949417114,0.0,1744060582.8970473,14.641289949417114,-22627416989.969524,1744060582.897048,14.641289949417114,0.0,1744060582.8970492,14.641289949417114,28284271247.461903
+1744060582.916882,14.661221504211426,-7.324209430571672,1744060582.916884,14.661221504211426,-31.83059407567148,1744060582.916886,14.661221504211426,0.0,1744060582.9168882,14.661221504211426,56568542496.923805,1744060582.9168894,14.661221504211426,0.0,1744060582.9168904,14.661221504211426,5.626907229098427e-10,1744060582.9168916,14.661221504211426,31.830594075671478,1744060582.9168928,14.661221504211426,4.583605545385658e-20,1744060582.916894,14.661221504211426,10,1744060582.9168947,14.661221504211426,0.0,1744060582.9168956,14.661221504211426,-22627416989.969524,1744060582.9168968,14.661221504211426,0.0,1744060582.9168978,14.661221504211426,28284271247.461903
+1744060582.9368658,14.681215047836304,-7.324209430571672,1744060582.9368675,14.681215047836304,-31.83059407567148,1744060582.9368696,14.681215047836304,0.0,1744060582.9368718,14.681215047836304,56568542496.923805,1744060582.9368727,14.681215047836304,0.0,1744060582.936874,14.681215047836304,5.626907229098427e-10,1744060582.936875,14.681215047836304,31.830594075671478,1744060582.936876,14.681215047836304,4.583605545385658e-20,1744060582.936877,14.681215047836304,10,1744060582.936878,14.681215047836304,0.0,1744060582.9368792,14.681215047836304,-22627416989.969524,1744060582.9368804,14.681215047836304,0.0,1744060582.9368813,14.681215047836304,28284271247.461903
+1744060582.957579,14.70127010345459,-7.324209430571672,1744060582.9575813,14.70127010345459,-31.83059407567148,1744060582.9575834,14.70127010345459,0.0,1744060582.9575856,14.70127010345459,56568542496.923805,1744060582.9575868,14.70127010345459,0.0,1744060582.9575882,14.70127010345459,5.626907229098427e-10,1744060582.9575894,14.70127010345459,31.830594075671478,1744060582.9575908,14.70127010345459,4.583605545385658e-20,1744060582.9575918,14.70127010345459,10,1744060582.9575932,14.70127010345459,0.0,1744060582.9575946,14.70127010345459,-22627416989.969524,1744060582.9575956,14.70127010345459,0.0,1744060582.9575968,14.70127010345459,28284271247.461903
+1744060582.9769306,14.721225023269653,-7.324209430571672,1744060582.9769323,14.721225023269653,-31.83059407567148,1744060582.9769344,14.721225023269653,0.0,1744060582.9769363,14.721225023269653,56568542496.923805,1744060582.9769375,14.721225023269653,0.0,1744060582.9769387,14.721225023269653,5.626907229098427e-10,1744060582.97694,14.721225023269653,31.830594075671478,1744060582.976941,14.721225023269653,4.583605545385658e-20,1744060582.9769423,14.721225023269653,10,1744060582.976943,14.721225023269653,0.0,1744060582.9769444,14.721225023269653,-22627416989.969524,1744060582.9769452,14.721225023269653,0.0,1744060582.976946,14.721225023269653,28284271247.461903
+1744060582.9970653,14.74126935005188,-7.324209430571672,1744060582.997067,14.74126935005188,-31.83059407567148,1744060582.9970694,14.74126935005188,0.0,1744060582.9970713,14.74126935005188,56568542496.923805,1744060582.9970725,14.74126935005188,0.0,1744060582.9970737,14.74126935005188,5.626907229098427e-10,1744060582.9970746,14.74126935005188,31.830594075671478,1744060582.997076,14.74126935005188,4.583605545385658e-20,1744060582.997077,14.74126935005188,10,1744060582.997078,14.74126935005188,0.0,1744060582.9970791,14.74126935005188,-22627416989.969524,1744060582.99708,14.74126935005188,0.0,1744060582.997081,14.74126935005188,28284271247.461903
+1744060583.0169132,14.761219024658203,-7.324209430571672,1744060583.016915,14.761219024658203,-31.83059407567148,1744060583.0169172,14.761219024658203,0.0,1744060583.0169196,14.761219024658203,56568542496.923805,1744060583.0169206,14.761219024658203,0.0,1744060583.0169218,14.761219024658203,5.626907229098427e-10,1744060583.016923,14.761219024658203,31.830594075671478,1744060583.016924,14.761219024658203,4.583605545385658e-20,1744060583.0169249,14.761219024658203,10,1744060583.0169263,14.761219024658203,0.0,1744060583.016927,14.761219024658203,-22627416989.969524,1744060583.016928,14.761219024658203,0.0,1744060583.016929,14.761219024658203,28284271247.461903
+1744060583.0371308,14.781311511993408,-7.324209430571672,1744060583.0371325,14.781311511993408,-31.83059407567148,1744060583.037135,14.781311511993408,0.0,1744060583.0371368,14.781311511993408,56568542496.923805,1744060583.0371568,14.781311511993408,0.0,1744060583.0371583,14.781311511993408,5.626907229098427e-10,1744060583.0371592,14.781311511993408,31.830594075671478,1744060583.0371604,14.781311511993408,4.583605545385658e-20,1744060583.0371616,14.781311511993408,10,1744060583.0371628,14.781311511993408,0.0,1744060583.0371637,14.781311511993408,-22627416989.969524,1744060583.0371647,14.781311511993408,0.0,1744060583.0371659,14.781311511993408,28284271247.461903
+1744060583.0577724,14.801300048828125,-7.324209430571672,1744060583.0577743,14.801300048828125,-31.83059407567148,1744060583.0577765,14.801300048828125,0.0,1744060583.0577781,14.801300048828125,56568542496.923805,1744060583.0577793,14.801300048828125,0.0,1744060583.0577805,14.801300048828125,5.626907229098427e-10,1744060583.0577815,14.801300048828125,31.830594075671478,1744060583.057783,14.801300048828125,4.583605545385658e-20,1744060583.0577838,14.801300048828125,10,1744060583.0577848,14.801300048828125,0.0,1744060583.0577857,14.801300048828125,-22627416989.969524,1744060583.0577867,14.801300048828125,0.0,1744060583.0577877,14.801300048828125,28284271247.461903
+1744060583.0769186,14.821253538131714,-7.324209430571672,1744060583.0769203,14.821253538131714,-31.83059407567148,1744060583.0769224,14.821253538131714,0.0,1744060583.0769243,14.821253538131714,56568542496.923805,1744060583.0769255,14.821253538131714,0.0,1744060583.0769267,14.821253538131714,5.626907229098427e-10,1744060583.076928,14.821253538131714,31.830594075671478,1744060583.076929,14.821253538131714,4.583605545385658e-20,1744060583.07693,14.821253538131714,10,1744060583.076931,14.821253538131714,0.0,1744060583.0769322,14.821253538131714,-22627416989.969524,1744060583.0769331,14.821253538131714,0.0,1744060583.076934,14.821253538131714,28284271247.461903
+1744060583.096947,14.841253519058228,-7.324209430571672,1744060583.0969486,14.841253519058228,-31.83059407567148,1744060583.0969508,14.841253519058228,0.0,1744060583.096953,14.841253519058228,56568542496.923805,1744060583.096954,14.841253519058228,0.0,1744060583.096955,14.841253519058228,5.626907229098427e-10,1744060583.0969563,14.841253519058228,31.830594075671478,1744060583.0969574,14.841253519058228,4.583605545385658e-20,1744060583.0969584,14.841253519058228,10,1744060583.096959,14.841253519058228,0.0,1744060583.0969603,14.841253519058228,-22627416989.969524,1744060583.0969613,14.841253519058228,0.0,1744060583.0969622,14.841253519058228,28284271247.461903
+1744060583.1171837,14.861277103424072,-7.324209430571672,1744060583.1171858,14.861277103424072,-31.83059407567148,1744060583.1171877,14.861277103424072,0.0,1744060583.11719,14.861277103424072,56568542496.923805,1744060583.117191,14.861277103424072,0.0,1744060583.1171923,14.861277103424072,5.626907229098427e-10,1744060583.1171935,14.861277103424072,31.830594075671478,1744060583.1171944,14.861277103424072,4.583605545385658e-20,1744060583.1171958,14.861277103424072,10,1744060583.1171966,14.861277103424072,0.0,1744060583.1171975,14.861277103424072,-22627416989.969524,1744060583.1171987,14.861277103424072,0.0,1744060583.1171997,14.861277103424072,28284271247.461903
+1744060583.1369092,14.881225347518921,-7.324209430571672,1744060583.1369112,14.881225347518921,-31.83059407567148,1744060583.1369133,14.881225347518921,0.0,1744060583.1369157,14.881225347518921,56568542496.923805,1744060583.1369166,14.881225347518921,0.0,1744060583.1369178,14.881225347518921,5.626907229098427e-10,1744060583.136919,14.881225347518921,31.830594075671478,1744060583.13692,14.881225347518921,4.583605545385658e-20,1744060583.1369212,14.881225347518921,10,1744060583.1369221,14.881225347518921,0.0,1744060583.136923,14.881225347518921,-22627416989.969524,1744060583.1369243,14.881225347518921,0.0,1744060583.1369252,14.881225347518921,28284271247.461903
+1744060583.157392,14.901256322860718,-7.324209430571672,1744060583.1573942,14.901256322860718,-31.83059407567148,1744060583.1573963,14.901256322860718,0.0,1744060583.1573987,14.901256322860718,56568542496.923805,1744060583.1574,14.901256322860718,0.0,1744060583.157401,14.901256322860718,5.626907229098427e-10,1744060583.1574023,14.901256322860718,31.830594075671478,1744060583.1574037,14.901256322860718,4.583605545385658e-20,1744060583.1574047,14.901256322860718,10,1744060583.1574054,14.901256322860718,0.0,1744060583.1574066,14.901256322860718,-22627416989.969524,1744060583.1574078,14.901256322860718,0.0,1744060583.1574085,14.901256322860718,28284271247.461903
+1744060583.1768725,14.92122197151184,-7.324209430571672,1744060583.1768742,14.92122197151184,-31.83059407567148,1744060583.1768763,14.92122197151184,0.0,1744060583.1768785,14.92122197151184,56568542496.923805,1744060583.1768794,14.92122197151184,0.0,1744060583.1768804,14.92122197151184,5.626907229098427e-10,1744060583.1768816,14.92122197151184,31.830594075671478,1744060583.1768827,14.92122197151184,4.583605545385658e-20,1744060583.1768837,14.92122197151184,10,1744060583.1768847,14.92122197151184,0.0,1744060583.1768858,14.92122197151184,-22627416989.969524,1744060583.1768868,14.92122197151184,0.0,1744060583.1768875,14.92122197151184,28284271247.461903
+1744060583.1974268,14.941271781921387,-7.324209430571672,1744060583.1974297,14.941271781921387,-31.83059407567148,1744060583.1974342,14.941271781921387,0.0,1744060583.1974387,14.941271781921387,56568542496.923805,1744060583.19744,14.941271781921387,0.0,1744060583.1974418,14.941271781921387,5.626907229098427e-10,1744060583.1974435,14.941271781921387,31.830594075671478,1744060583.1974452,14.941271781921387,4.583605545385658e-20,1744060583.1974466,14.941271781921387,10,1744060583.197448,14.941271781921387,0.0,1744060583.1974494,14.941271781921387,-22627416989.969524,1744060583.1974506,14.941271781921387,0.0,1744060583.1974523,14.941271781921387,28284271247.461903
+1744060583.2174475,14.961283206939697,-7.324209430571672,1744060583.2174492,14.961283206939697,-31.83059407567148,1744060583.2174513,14.961283206939697,0.0,1744060583.2174537,14.961283206939697,56568542496.923805,1744060583.217455,14.961283206939697,0.0,1744060583.217456,14.961283206939697,5.626907229098427e-10,1744060583.2174573,14.961283206939697,31.830594075671478,1744060583.2174587,14.961283206939697,4.583605545385658e-20,1744060583.2174597,14.961283206939697,10,1744060583.2174606,14.961283206939697,0.0,1744060583.2174618,14.961283206939697,-22627416989.969524,1744060583.2174625,14.961283206939697,0.0,1744060583.2174635,14.961283206939697,28284271247.461903
+1744060583.2369568,14.981257438659668,-7.324209430571672,1744060583.2369587,14.981257438659668,-31.83059407567148,1744060583.2369611,14.981257438659668,0.0,1744060583.236963,14.981257438659668,56568542496.923805,1744060583.2369645,14.981257438659668,0.0,1744060583.2369654,14.981257438659668,5.626907229098427e-10,1744060583.2369664,14.981257438659668,31.830594075671478,1744060583.2369676,14.981257438659668,4.583605545385658e-20,1744060583.2369688,14.981257438659668,10,1744060583.2369697,14.981257438659668,0.0,1744060583.2369707,14.981257438659668,-22627416989.969524,1744060583.2369719,14.981257438659668,0.0,1744060583.2369726,14.981257438659668,28284271247.461903
+1744060583.2572677,15.001262903213501,-7.270969720684385,1744060583.2572696,15.001262903213501,-31.972590458514272,1744060583.2572715,15.001262903213501,0.0,1744060583.2572737,15.001262903213501,56568542496.923805,1744060583.2572746,15.001262903213501,0.0,1744060583.2572758,15.001262903213501,5.652008880402633e-10,1744060583.257277,15.001262903213501,31.972590458514272,1744060583.257278,15.001262903213501,4.604053024516945e-20,1744060583.2572792,15.001262903213501,10,1744060583.25728,15.001262903213501,0.0,1744060583.2572813,15.001262903213501,-22627416989.969524,1744060583.257282,15.001262903213501,0.0,1744060583.257283,15.001262903213501,28284271247.461903
+1744060583.2770884,15.021256446838379,-7.270969720684385,1744060583.2770903,15.021256446838379,-31.972590458514272,1744060583.2770925,15.021256446838379,0.0,1744060583.2770944,15.021256446838379,56568542496.923805,1744060583.2770953,15.021256446838379,0.0,1744060583.2770967,15.021256446838379,5.652008880402633e-10,1744060583.277098,15.021256446838379,31.972590458514272,1744060583.277099,15.021256446838379,4.604053024516945e-20,1744060583.2771006,15.021256446838379,10,1744060583.2771015,15.021256446838379,0.0,1744060583.2771027,15.021256446838379,-22627416989.969524,1744060583.2771034,15.021256446838379,0.0,1744060583.2771044,15.021256446838379,28284271247.461903
+1744060583.297468,15.041318893432617,-7.270969720684385,1744060583.2974706,15.041318893432617,-31.972590458514272,1744060583.2974727,15.041318893432617,0.0,1744060583.2974753,15.041318893432617,56568542496.923805,1744060583.297477,15.041318893432617,0.0,1744060583.2974784,15.041318893432617,5.652008880402633e-10,1744060583.2974796,15.041318893432617,31.972590458514272,1744060583.297481,15.041318893432617,4.604053024516945e-20,1744060583.297482,15.041318893432617,10,1744060583.297483,15.041318893432617,0.0,1744060583.297484,15.041318893432617,-22627416989.969524,1744060583.297485,15.041318893432617,0.0,1744060583.2975054,15.041318893432617,28284271247.461903
+1744060583.3169029,15.061249732971191,-7.270969720684385,1744060583.316905,15.061249732971191,-31.972590458514272,1744060583.3169067,15.061249732971191,0.0,1744060583.3169088,15.061249732971191,56568542496.923805,1744060583.3169098,15.061249732971191,0.0,1744060583.3169112,15.061249732971191,5.652008880402633e-10,1744060583.3169122,15.061249732971191,31.972590458514272,1744060583.3169131,15.061249732971191,4.604053024516945e-20,1744060583.3169143,15.061249732971191,10,1744060583.3169153,15.061249732971191,0.0,1744060583.3169162,15.061249732971191,-22627416989.969524,1744060583.3169172,15.061249732971191,0.0,1744060583.3169184,15.061249732971191,28284271247.461903
+1744060583.336932,15.08122444152832,-7.270969720684385,1744060583.3369336,15.08122444152832,-31.972590458514272,1744060583.3369358,15.08122444152832,0.0,1744060583.336938,15.08122444152832,56568542496.923805,1744060583.336939,15.08122444152832,0.0,1744060583.3369403,15.08122444152832,5.652008880402633e-10,1744060583.3369412,15.08122444152832,31.972590458514272,1744060583.3369427,15.08122444152832,4.604053024516945e-20,1744060583.3369436,15.08122444152832,10,1744060583.3369443,15.08122444152832,0.0,1744060583.3369453,15.08122444152832,-22627416989.969524,1744060583.3369465,15.08122444152832,0.0,1744060583.3369474,15.08122444152832,28284271247.461903
+1744060583.3572514,15.101224184036255,-7.270969720684385,1744060583.3572536,15.101224184036255,-31.972590458514272,1744060583.357256,15.101224184036255,0.0,1744060583.3572586,15.101224184036255,56568542496.923805,1744060583.3572598,15.101224184036255,0.0,1744060583.3572607,15.101224184036255,5.652008880402633e-10,1744060583.3572626,15.101224184036255,31.972590458514272,1744060583.3572636,15.101224184036255,4.604053024516945e-20,1744060583.357265,15.101224184036255,10,1744060583.357266,15.101224184036255,0.0,1744060583.3572674,15.101224184036255,-22627416989.969524,1744060583.3572686,15.101224184036255,0.0,1744060583.3572695,15.101224184036255,28284271247.461903
+1744060583.3769186,15.121248722076416,-7.270969720684385,1744060583.3769202,15.121248722076416,-31.972590458514272,1744060583.3769224,15.121248722076416,0.0,1744060583.3769245,15.121248722076416,56568542496.923805,1744060583.3769257,15.121248722076416,0.0,1744060583.376927,15.121248722076416,5.652008880402633e-10,1744060583.376928,15.121248722076416,31.972590458514272,1744060583.376929,15.121248722076416,4.604053024516945e-20,1744060583.37693,15.121248722076416,10,1744060583.3769312,15.121248722076416,0.0,1744060583.3769321,15.121248722076416,-22627416989.969524,1744060583.376933,15.121248722076416,0.0,1744060583.3769343,15.121248722076416,28284271247.461903
+1744060583.397099,15.141236305236816,-7.270969720684385,1744060583.3971007,15.141236305236816,-31.972590458514272,1744060583.3971028,15.141236305236816,0.0,1744060583.3971052,15.141236305236816,56568542496.923805,1744060583.3971062,15.141236305236816,0.0,1744060583.3971074,15.141236305236816,5.652008880402633e-10,1744060583.3971088,15.141236305236816,31.972590458514272,1744060583.3971097,15.141236305236816,4.604053024516945e-20,1744060583.3971107,15.141236305236816,10,1744060583.3971117,15.141236305236816,0.0,1744060583.3971128,15.141236305236816,-22627416989.969524,1744060583.397114,15.141236305236816,0.0,1744060583.397115,15.141236305236816,28284271247.461903
+1744060583.4168794,15.161216974258423,-7.270969720684385,1744060583.416881,15.161216974258423,-31.972590458514272,1744060583.4168832,15.161216974258423,0.0,1744060583.4168851,15.161216974258423,56568542496.923805,1744060583.4168863,15.161216974258423,0.0,1744060583.4168875,15.161216974258423,5.652008880402633e-10,1744060583.4168887,15.161216974258423,31.972590458514272,1744060583.41689,15.161216974258423,4.604053024516945e-20,1744060583.4168909,15.161216974258423,10,1744060583.4168918,15.161216974258423,0.0,1744060583.416893,15.161216974258423,-22627416989.969524,1744060583.4168937,15.161216974258423,0.0,1744060583.4168947,15.161216974258423,28284271247.461903
+1744060583.437034,15.181260585784912,-7.270969720684385,1744060583.437036,15.181260585784912,-31.972590458514272,1744060583.4370384,15.181260585784912,0.0,1744060583.4370408,15.181260585784912,56568542496.923805,1744060583.4370422,15.181260585784912,0.0,1744060583.4370434,15.181260585784912,5.652008880402633e-10,1744060583.4370446,15.181260585784912,31.972590458514272,1744060583.437046,15.181260585784912,4.604053024516945e-20,1744060583.4370472,15.181260585784912,10,1744060583.4370484,15.181260585784912,0.0,1744060583.4370494,15.181260585784912,-22627416989.969524,1744060583.4370506,15.181260585784912,0.0,1744060583.4370515,15.181260585784912,28284271247.461903
+1744060583.4577427,15.201303958892822,-7.270969720684385,1744060583.4577446,15.201303958892822,-31.972590458514272,1744060583.457747,15.201303958892822,0.0,1744060583.457749,15.201303958892822,56568542496.923805,1744060583.45775,15.201303958892822,0.0,1744060583.457751,15.201303958892822,5.652008880402633e-10,1744060583.4577522,15.201303958892822,31.972590458514272,1744060583.4577534,15.201303958892822,4.604053024516945e-20,1744060583.4577546,15.201303958892822,10,1744060583.4577556,15.201303958892822,0.0,1744060583.4577565,15.201303958892822,-22627416989.969524,1744060583.4577575,15.201303958892822,0.0,1744060583.4577584,15.201303958892822,28284271247.461903
+1744060583.4769223,15.221249103546143,-7.270969720684385,1744060583.4769242,15.221249103546143,-31.972590458514272,1744060583.4769258,15.221249103546143,0.0,1744060583.4769282,15.221249103546143,56568542496.923805,1744060583.4769292,15.221249103546143,0.0,1744060583.4769304,15.221249103546143,5.652008880402633e-10,1744060583.4769316,15.221249103546143,31.972590458514272,1744060583.4769325,15.221249103546143,4.604053024516945e-20,1744060583.4769337,15.221249103546143,10,1744060583.4769347,15.221249103546143,0.0,1744060583.4769356,15.221249103546143,-22627416989.969524,1744060583.4769363,15.221249103546143,0.0,1744060583.4769375,15.221249103546143,28284271247.461903
+1744060583.497067,15.241228580474854,-7.270969720684385,1744060583.4970691,15.241228580474854,-31.972590458514272,1744060583.497071,15.241228580474854,0.0,1744060583.4970734,15.241228580474854,56568542496.923805,1744060583.4970744,15.241228580474854,0.0,1744060583.4970758,15.241228580474854,5.652008880402633e-10,1744060583.497077,15.241228580474854,31.972590458514272,1744060583.4970782,15.241228580474854,4.604053024516945e-20,1744060583.4970794,15.241228580474854,10,1744060583.4970803,15.241228580474854,0.0,1744060583.4970813,15.241228580474854,-22627416989.969524,1744060583.4970825,15.241228580474854,0.0,1744060583.4970834,15.241228580474854,28284271247.461903
+1744060583.5175314,15.2612943649292,-7.270969720684385,1744060583.5175335,15.2612943649292,-31.972590458514272,1744060583.5175357,15.2612943649292,0.0,1744060583.517538,15.2612943649292,56568542496.923805,1744060583.517539,15.2612943649292,0.0,1744060583.5175405,15.2612943649292,5.652008880402633e-10,1744060583.5175416,15.2612943649292,31.972590458514272,1744060583.5175426,15.2612943649292,4.604053024516945e-20,1744060583.517544,15.2612943649292,10,1744060583.517545,15.2612943649292,0.0,1744060583.5175462,15.2612943649292,-22627416989.969524,1744060583.5175474,15.2612943649292,0.0,1744060583.5175483,15.2612943649292,28284271247.461903
+1744060583.537105,15.281282901763916,-7.270969720684385,1744060583.537107,15.281282901763916,-31.972590458514272,1744060583.5371091,15.281282901763916,0.0,1744060583.5371113,15.281282901763916,56568542496.923805,1744060583.5371125,15.281282901763916,0.0,1744060583.5371137,15.281282901763916,5.652008880402633e-10,1744060583.5371149,15.281282901763916,31.972590458514272,1744060583.537116,15.281282901763916,4.604053024516945e-20,1744060583.5371172,15.281282901763916,10,1744060583.5371182,15.281282901763916,0.0,1744060583.5371192,15.281282901763916,-22627416989.969524,1744060583.5371203,15.281282901763916,0.0,1744060583.5371213,15.281282901763916,28284271247.461903
+1744060583.558622,15.301243782043457,-7.270969720684385,1744060583.558624,15.301243782043457,-31.972590458514272,1744060583.558626,15.301243782043457,0.0,1744060583.5586283,15.301243782043457,56568542496.923805,1744060583.5586293,15.301243782043457,0.0,1744060583.5586307,15.301243782043457,5.652008880402633e-10,1744060583.558632,15.301243782043457,31.972590458514272,1744060583.5586329,15.301243782043457,4.604053024516945e-20,1744060583.5586343,15.301243782043457,10,1744060583.5586355,15.301243782043457,0.0,1744060583.5586364,15.301243782043457,-22627416989.969524,1744060583.5586376,15.301243782043457,0.0,1744060583.5586386,15.301243782043457,28284271247.461903
+1744060583.5769286,15.321223735809326,-7.270969720684385,1744060583.5769303,15.321223735809326,-31.972590458514272,1744060583.5769327,15.321223735809326,0.0,1744060583.5769346,15.321223735809326,56568542496.923805,1744060583.576936,15.321223735809326,0.0,1744060583.576937,15.321223735809326,5.652008880402633e-10,1744060583.576938,15.321223735809326,31.972590458514272,1744060583.5769393,15.321223735809326,4.604053024516945e-20,1744060583.5769403,15.321223735809326,10,1744060583.5769413,15.321223735809326,0.0,1744060583.5769424,15.321223735809326,-22627416989.969524,1744060583.5769434,15.321223735809326,0.0,1744060583.576944,15.321223735809326,28284271247.461903
+1744060583.5972295,15.341289281845093,-7.270969720684385,1744060583.5972316,15.341289281845093,-31.972590458514272,1744060583.597234,15.341289281845093,0.0,1744060583.5972362,15.341289281845093,56568542496.923805,1744060583.5972373,15.341289281845093,0.0,1744060583.5972385,15.341289281845093,5.652008880402633e-10,1744060583.5972397,15.341289281845093,31.972590458514272,1744060583.5972412,15.341289281845093,4.604053024516945e-20,1744060583.597242,15.341289281845093,10,1744060583.5972433,15.341289281845093,0.0,1744060583.5972445,15.341289281845093,-22627416989.969524,1744060583.5972455,15.341289281845093,0.0,1744060583.5972464,15.341289281845093,28284271247.461903
+1744060583.6172938,15.361268758773804,-7.270969720684385,1744060583.617296,15.361268758773804,-31.972590458514272,1744060583.6172981,15.361268758773804,0.0,1744060583.6173003,15.361268758773804,56568542496.923805,1744060583.6173012,15.361268758773804,0.0,1744060583.6173024,15.361268758773804,5.652008880402633e-10,1744060583.6173038,15.361268758773804,31.972590458514272,1744060583.617322,15.361268758773804,4.604053024516945e-20,1744060583.6173232,15.361268758773804,10,1744060583.6173246,15.361268758773804,0.0,1744060583.6173253,15.361268758773804,-22627416989.969524,1744060583.6173263,15.361268758773804,0.0,1744060583.6173275,15.361268758773804,28284271247.461903
+1744060583.6372411,15.381286382675171,-7.270969720684385,1744060583.637243,15.381286382675171,-31.972590458514272,1744060583.6372452,15.381286382675171,0.0,1744060583.6372478,15.381286382675171,56568542496.923805,1744060583.637249,15.381286382675171,0.0,1744060583.6372502,15.381286382675171,5.652008880402633e-10,1744060583.6372519,15.381286382675171,31.972590458514272,1744060583.6372528,15.381286382675171,4.604053024516945e-20,1744060583.6372545,15.381286382675171,10,1744060583.6372557,15.381286382675171,0.0,1744060583.6372569,15.381286382675171,-22627416989.969524,1744060583.6372585,15.381286382675171,0.0,1744060583.6372595,15.381286382675171,28284271247.461903
+1744060583.6576297,15.401225328445435,-7.270969720684385,1744060583.6576316,15.401225328445435,-31.972590458514272,1744060583.6576338,15.401225328445435,0.0,1744060583.657636,15.401225328445435,56568542496.923805,1744060583.657637,15.401225328445435,0.0,1744060583.657638,15.401225328445435,5.652008880402633e-10,1744060583.6576395,15.401225328445435,31.972590458514272,1744060583.6576405,15.401225328445435,4.604053024516945e-20,1744060583.6576414,15.401225328445435,10,1744060583.6576426,15.401225328445435,0.0,1744060583.6576436,15.401225328445435,-22627416989.969524,1744060583.6576445,15.401225328445435,0.0,1744060583.6576452,15.401225328445435,28284271247.461903
+1744060583.6769128,15.421256303787231,-7.270969720684385,1744060583.6769147,15.421256303787231,-31.972590458514272,1744060583.6769168,15.421256303787231,0.0,1744060583.6769192,15.421256303787231,56568542496.923805,1744060583.6769204,15.421256303787231,0.0,1744060583.6769216,15.421256303787231,5.652008880402633e-10,1744060583.6769228,15.421256303787231,31.972590458514272,1744060583.676924,15.421256303787231,4.604053024516945e-20,1744060583.676925,15.421256303787231,10,1744060583.676926,15.421256303787231,0.0,1744060583.676927,15.421256303787231,-22627416989.969524,1744060583.6769278,15.421256303787231,0.0,1744060583.6769288,15.421256303787231,28284271247.461903
+1744060583.697183,15.441231727600098,-7.270969720684385,1744060583.6971848,15.441231727600098,-31.972590458514272,1744060583.6971867,15.441231727600098,0.0,1744060583.6971889,15.441231727600098,56568542496.923805,1744060583.6972072,15.441231727600098,0.0,1744060583.697209,15.441231727600098,5.652008880402633e-10,1744060583.69721,15.441231727600098,31.972590458514272,1744060583.697211,15.441231727600098,4.604053024516945e-20,1744060583.6972122,15.441231727600098,10,1744060583.6972132,15.441231727600098,0.0,1744060583.697214,15.441231727600098,-22627416989.969524,1744060583.697215,15.441231727600098,0.0,1744060583.697216,15.441231727600098,28284271247.461903
+1744060583.7170706,15.461255550384521,-7.270969720684385,1744060583.717072,15.461255550384521,-31.972590458514272,1744060583.7170742,15.461255550384521,0.0,1744060583.7170768,15.461255550384521,56568542496.923805,1744060583.7170777,15.461255550384521,0.0,1744060583.7170787,15.461255550384521,5.652008880402633e-10,1744060583.71708,15.461255550384521,31.972590458514272,1744060583.717081,15.461255550384521,4.604053024516945e-20,1744060583.717082,15.461255550384521,10,1744060583.7170835,15.461255550384521,0.0,1744060583.7170844,15.461255550384521,-22627416989.969524,1744060583.7170854,15.461255550384521,0.0,1744060583.7170866,15.461255550384521,28284271247.461903
+1744060583.7371156,15.481221437454224,-7.270969720684385,1744060583.737118,15.481221437454224,-31.972590458514272,1744060583.7371202,15.481221437454224,0.0,1744060583.7371228,15.481221437454224,56568542496.923805,1744060583.7371237,15.481221437454224,0.0,1744060583.7371254,15.481221437454224,5.652008880402633e-10,1744060583.7371268,15.481221437454224,31.972590458514272,1744060583.7371283,15.481221437454224,4.604053024516945e-20,1744060583.7371297,15.481221437454224,10,1744060583.737131,15.481221437454224,0.0,1744060583.7371323,15.481221437454224,-22627416989.969524,1744060583.7371335,15.481221437454224,0.0,1744060583.737135,15.481221437454224,28284271247.461903
+1744060583.758609,15.501266241073608,-7.16608581930581,1744060583.758614,15.501266241073608,-32.026576259766706,1744060583.7586176,15.501266241073608,0.0,1744060583.7586215,15.501266241073608,56568542496.923805,1744060583.758641,15.501266241073608,0.0,1744060583.7586436,15.501266241073608,5.661552311949913e-10,1744060583.758647,15.501266241073608,32.026576259766706,1744060583.7586496,15.501266241073608,4.611826979911849e-20,1744060583.7586524,15.501266241073608,10,1744060583.7586553,15.501266241073608,0.0,1744060583.7586575,15.501266241073608,-22627416989.969524,1744060583.7586598,15.501266241073608,0.0,1744060583.7586622,15.501266241073608,28284271247.461903
+1744060583.7773557,15.521249771118164,-7.16608581930581,1744060583.7773588,15.521249771118164,-32.026576259766706,1744060583.7773626,15.521249771118164,0.0,1744060583.7773736,15.521249771118164,56568542496.923805,1744060583.7773774,15.521249771118164,0.0,1744060583.7773793,15.521249771118164,5.661552311949913e-10,1744060583.7773812,15.521249771118164,32.026576259766706,1744060583.777383,15.521249771118164,4.611826979911849e-20,1744060583.7773852,15.521249771118164,10,1744060583.777387,15.521249771118164,0.0,1744060583.7773893,15.521249771118164,-22627416989.969524,1744060583.7773929,15.521249771118164,0.0,1744060583.7773945,15.521249771118164,28284271247.461903
+1744060583.7971122,15.54132342338562,-7.16608581930581,1744060583.7971141,15.54132342338562,-32.026576259766706,1744060583.7971165,15.54132342338562,0.0,1744060583.7971184,15.54132342338562,56568542496.923805,1744060583.7971194,15.54132342338562,0.0,1744060583.7971208,15.54132342338562,5.661552311949913e-10,1744060583.797122,15.54132342338562,32.026576259766706,1744060583.797123,15.54132342338562,4.611826979911849e-20,1744060583.7971241,15.54132342338562,10,1744060583.797125,15.54132342338562,0.0,1744060583.797126,15.54132342338562,-22627416989.969524,1744060583.797127,15.54132342338562,0.0,1744060583.797128,15.54132342338562,28284271247.461903
+1744060583.8171105,15.561270236968994,-7.16608581930581,1744060583.8171122,15.561270236968994,-32.026576259766706,1744060583.8171146,15.561270236968994,0.0,1744060583.8171167,15.561270236968994,56568542496.923805,1744060583.8171182,15.561270236968994,0.0,1744060583.8171196,15.561270236968994,5.661552311949913e-10,1744060583.8171208,15.561270236968994,32.026576259766706,1744060583.8171217,15.561270236968994,4.611826979911849e-20,1744060583.8171232,15.561270236968994,10,1744060583.817124,15.561270236968994,0.0,1744060583.8171248,15.561270236968994,-22627416989.969524,1744060583.8171258,15.561270236968994,0.0,1744060583.817127,15.561270236968994,28284271247.461903
+1744060583.8372872,15.581266403198242,-7.16608581930581,1744060583.8372893,15.581266403198242,-32.026576259766706,1744060583.8372915,15.581266403198242,0.0,1744060583.8372943,15.581266403198242,56568542496.923805,1744060583.8372955,15.581266403198242,0.0,1744060583.837297,15.581266403198242,5.661552311949913e-10,1744060583.8372982,15.581266403198242,32.026576259766706,1744060583.8372993,15.581266403198242,4.611826979911849e-20,1744060583.837301,15.581266403198242,10,1744060583.8373022,15.581266403198242,0.0,1744060583.8373034,15.581266403198242,-22627416989.969524,1744060583.8373044,15.581266403198242,0.0,1744060583.8373053,15.581266403198242,28284271247.461903
+1744060583.8581822,15.601311206817627,-7.16608581930581,1744060583.8581839,15.601311206817627,-32.026576259766706,1744060583.858186,15.601311206817627,0.0,1744060583.8581886,15.601311206817627,56568542496.923805,1744060583.8581893,15.601311206817627,0.0,1744060583.8581905,15.601311206817627,5.661552311949913e-10,1744060583.8582084,15.601311206817627,32.026576259766706,1744060583.8582096,15.601311206817627,4.611826979911849e-20,1744060583.8582106,15.601311206817627,10,1744060583.8582115,15.601311206817627,0.0,1744060583.8582127,15.601311206817627,-22627416989.969524,1744060583.8582134,15.601311206817627,0.0,1744060583.8582144,15.601311206817627,28284271247.461903
+1744060583.8769636,15.621248483657837,-7.16608581930581,1744060583.8769653,15.621248483657837,-32.026576259766706,1744060583.8769674,15.621248483657837,0.0,1744060583.8769696,15.621248483657837,56568542496.923805,1744060583.8769705,15.621248483657837,0.0,1744060583.8769715,15.621248483657837,5.661552311949913e-10,1744060583.8769732,15.621248483657837,32.026576259766706,1744060583.876974,15.621248483657837,4.611826979911849e-20,1744060583.876975,15.621248483657837,10,1744060583.876976,15.621248483657837,0.0,1744060583.8769772,15.621248483657837,-22627416989.969524,1744060583.8769782,15.621248483657837,0.0,1744060583.876979,15.621248483657837,28284271247.461903
+1744060583.897126,15.641274690628052,-7.16608581930581,1744060583.8971276,15.641274690628052,-32.026576259766706,1744060583.8971298,15.641274690628052,0.0,1744060583.897132,15.641274690628052,56568542496.923805,1744060583.8971336,15.641274690628052,0.0,1744060583.8971348,15.641274690628052,5.661552311949913e-10,1744060583.897136,15.641274690628052,32.026576259766706,1744060583.8971372,15.641274690628052,4.611826979911849e-20,1744060583.897138,15.641274690628052,10,1744060583.8971388,15.641274690628052,0.0,1744060583.89714,15.641274690628052,-22627416989.969524,1744060583.897141,15.641274690628052,0.0,1744060583.897142,15.641274690628052,28284271247.461903
+1744060583.9169288,15.661264181137085,-7.16608581930581,1744060583.9169307,15.661264181137085,-32.026576259766706,1744060583.9169326,15.661264181137085,0.0,1744060583.916935,15.661264181137085,56568542496.923805,1744060583.916936,15.661264181137085,0.0,1744060583.9169369,15.661264181137085,5.661552311949913e-10,1744060583.9169383,15.661264181137085,32.026576259766706,1744060583.9169395,15.661264181137085,4.611826979911849e-20,1744060583.9169405,15.661264181137085,10,1744060583.9169416,15.661264181137085,0.0,1744060583.9169424,15.661264181137085,-22627416989.969524,1744060583.9169433,15.661264181137085,0.0,1744060583.9169443,15.661264181137085,28284271247.461903
+1744060583.9371104,15.68127179145813,-7.16608581930581,1744060583.9371133,15.68127179145813,-32.026576259766706,1744060583.937116,15.68127179145813,0.0,1744060583.937119,15.68127179145813,56568542496.923805,1744060583.9371202,15.68127179145813,0.0,1744060583.9371223,15.68127179145813,5.661552311949913e-10,1744060583.9371238,15.68127179145813,32.026576259766706,1744060583.9371257,15.68127179145813,4.611826979911849e-20,1744060583.9371274,15.68127179145813,10,1744060583.9371293,15.68127179145813,0.0,1744060583.9371307,15.68127179145813,-22627416989.969524,1744060583.9371324,15.68127179145813,0.0,1744060583.9371338,15.68127179145813,28284271247.461903
+1744060583.9574103,15.70123028755188,-7.16608581930581,1744060583.957412,15.70123028755188,-32.026576259766706,1744060583.957414,15.70123028755188,0.0,1744060583.9574163,15.70123028755188,56568542496.923805,1744060583.9574172,15.70123028755188,0.0,1744060583.9574182,15.70123028755188,5.661552311949913e-10,1744060583.9574196,15.70123028755188,32.026576259766706,1744060583.9574206,15.70123028755188,4.611826979911849e-20,1744060583.9574215,15.70123028755188,10,1744060583.9574225,15.70123028755188,0.0,1744060583.9574237,15.70123028755188,-22627416989.969524,1744060583.9574246,15.70123028755188,0.0,1744060583.9574256,15.70123028755188,28284271247.461903
+1744060583.9769926,15.721240043640137,-7.16608581930581,1744060583.9769943,15.721240043640137,-32.026576259766706,1744060583.9769964,15.721240043640137,0.0,1744060583.9769986,15.721240043640137,56568542496.923805,1744060583.9769998,15.721240043640137,0.0,1744060583.977001,15.721240043640137,5.661552311949913e-10,1744060583.9770021,15.721240043640137,32.026576259766706,1744060583.9770033,15.721240043640137,4.611826979911849e-20,1744060583.9770045,15.721240043640137,10,1744060583.9770055,15.721240043640137,0.0,1744060583.9770064,15.721240043640137,-22627416989.969524,1744060583.9770074,15.721240043640137,0.0,1744060583.9770083,15.721240043640137,28284271247.461903
+1744060583.9973366,15.7412850856781,-7.16608581930581,1744060583.9973388,15.7412850856781,-32.026576259766706,1744060583.9973412,15.7412850856781,0.0,1744060583.9973435,15.7412850856781,56568542496.923805,1744060583.9973445,15.7412850856781,0.0,1744060583.9973457,15.7412850856781,5.661552311949913e-10,1744060583.9973474,15.7412850856781,32.026576259766706,1744060583.9973485,15.7412850856781,4.611826979911849e-20,1744060583.9973497,15.7412850856781,10,1744060583.9973507,15.7412850856781,0.0,1744060583.9973514,15.7412850856781,-22627416989.969524,1744060583.9973524,15.7412850856781,0.0,1744060583.9973536,15.7412850856781,28284271247.461903
+1744060584.0175564,15.761284828186035,-7.16608581930581,1744060584.0175586,15.761284828186035,-32.026576259766706,1744060584.0175612,15.761284828186035,0.0,1744060584.0175633,15.761284828186035,56568542496.923805,1744060584.0175645,15.761284828186035,0.0,1744060584.0175657,15.761284828186035,5.661552311949913e-10,1744060584.0175667,15.761284828186035,32.026576259766706,1744060584.0175683,15.761284828186035,4.611826979911849e-20,1744060584.0175693,15.761284828186035,10,1744060584.0175705,15.761284828186035,0.0,1744060584.0175712,15.761284828186035,-22627416989.969524,1744060584.0175724,15.761284828186035,0.0,1744060584.0175734,15.761284828186035,28284271247.461903
+1744060584.0369594,15.781260251998901,-7.16608581930581,1744060584.0369613,15.781260251998901,-32.026576259766706,1744060584.0369632,15.781260251998901,0.0,1744060584.0369656,15.781260251998901,56568542496.923805,1744060584.0369666,15.781260251998901,0.0,1744060584.036968,15.781260251998901,5.661552311949913e-10,1744060584.0369692,15.781260251998901,32.026576259766706,1744060584.0369701,15.781260251998901,4.611826979911849e-20,1744060584.0369716,15.781260251998901,10,1744060584.0369725,15.781260251998901,0.0,1744060584.0369735,15.781260251998901,-22627416989.969524,1744060584.0369747,15.781260251998901,0.0,1744060584.0369759,15.781260251998901,28284271247.461903
+1744060584.0573337,15.801294326782227,-7.16608581930581,1744060584.0573356,15.801294326782227,-32.026576259766706,1744060584.0573375,15.801294326782227,0.0,1744060584.05734,15.801294326782227,56568542496.923805,1744060584.0573406,15.801294326782227,0.0,1744060584.057342,15.801294326782227,5.661552311949913e-10,1744060584.0573432,15.801294326782227,32.026576259766706,1744060584.0573442,15.801294326782227,4.611826979911849e-20,1744060584.0573456,15.801294326782227,10,1744060584.0573466,15.801294326782227,0.0,1744060584.0573475,15.801294326782227,-22627416989.969524,1744060584.0573485,15.801294326782227,0.0,1744060584.0573494,15.801294326782227,28284271247.461903
+1744060584.077212,15.821248054504395,-7.16608581930581,1744060584.077214,15.821248054504395,-32.026576259766706,1744060584.0772161,15.821248054504395,0.0,1744060584.0772185,15.821248054504395,56568542496.923805,1744060584.0772195,15.821248054504395,0.0,1744060584.077221,15.821248054504395,5.661552311949913e-10,1744060584.0772219,15.821248054504395,32.026576259766706,1744060584.0772235,15.821248054504395,4.611826979911849e-20,1744060584.0772245,15.821248054504395,10,1744060584.0772254,15.821248054504395,0.0,1744060584.0772264,15.821248054504395,-22627416989.969524,1744060584.0772274,15.821248054504395,0.0,1744060584.0772283,15.821248054504395,28284271247.461903
+1744060584.0971205,15.841230630874634,-7.16608581930581,1744060584.0971234,15.841230630874634,-32.026576259766706,1744060584.0971267,15.841230630874634,0.0,1744060584.0971303,15.841230630874634,56568542496.923805,1744060584.097132,15.841230630874634,0.0,1744060584.0971339,15.841230630874634,5.661552311949913e-10,1744060584.0971355,15.841230630874634,32.026576259766706,1744060584.0971372,15.841230630874634,4.611826979911849e-20,1744060584.097139,15.841230630874634,10,1744060584.0971406,15.841230630874634,0.0,1744060584.097142,15.841230630874634,-22627416989.969524,1744060584.097144,15.841230630874634,0.0,1744060584.0971456,15.841230630874634,28284271247.461903
+1744060584.1171215,15.861279964447021,-7.16608581930581,1744060584.1171234,15.861279964447021,-32.026576259766706,1744060584.1171253,15.861279964447021,0.0,1744060584.1171277,15.861279964447021,56568542496.923805,1744060584.1171286,15.861279964447021,0.0,1744060584.11713,15.861279964447021,5.661552311949913e-10,1744060584.117131,15.861279964447021,32.026576259766706,1744060584.1171322,15.861279964447021,4.611826979911849e-20,1744060584.1171334,15.861279964447021,10,1744060584.1171343,15.861279964447021,0.0,1744060584.117135,15.861279964447021,-22627416989.969524,1744060584.1171362,15.861279964447021,0.0,1744060584.1171372,15.861279964447021,28284271247.461903
+1744060584.1369991,15.881296634674072,-7.16608581930581,1744060584.1370013,15.881296634674072,-32.026576259766706,1744060584.1370032,15.881296634674072,0.0,1744060584.1370056,15.881296634674072,56568542496.923805,1744060584.1370065,15.881296634674072,0.0,1744060584.1370077,15.881296634674072,5.661552311949913e-10,1744060584.1370087,15.881296634674072,32.026576259766706,1744060584.1370096,15.881296634674072,4.611826979911849e-20,1744060584.137011,15.881296634674072,10,1744060584.137012,15.881296634674072,0.0,1744060584.137013,15.881296634674072,-22627416989.969524,1744060584.1370137,15.881296634674072,0.0,1744060584.1370149,15.881296634674072,28284271247.461903
+1744060584.1574924,15.901235580444336,-7.16608581930581,1744060584.1575115,15.901235580444336,-32.026576259766706,1744060584.157514,15.901235580444336,0.0,1744060584.1575162,15.901235580444336,56568542496.923805,1744060584.1575172,15.901235580444336,0.0,1744060584.1575353,15.901235580444336,5.661552311949913e-10,1744060584.1575363,15.901235580444336,32.026576259766706,1744060584.1575375,15.901235580444336,4.611826979911849e-20,1744060584.1575387,15.901235580444336,10,1744060584.1575396,15.901235580444336,0.0,1744060584.1575403,15.901235580444336,-22627416989.969524,1744060584.1575413,15.901235580444336,0.0,1744060584.1575425,15.901235580444336,28284271247.461903
+1744060584.1769028,15.921221733093262,-7.16608581930581,1744060584.1769047,15.921221733093262,-32.026576259766706,1744060584.1769073,15.921221733093262,0.0,1744060584.1769283,15.921221733093262,56568542496.923805,1744060584.1769295,15.921221733093262,0.0,1744060584.176931,15.921221733093262,5.661552311949913e-10,1744060584.176932,15.921221733093262,32.026576259766706,1744060584.1769333,15.921221733093262,4.611826979911849e-20,1744060584.1769352,15.921221733093262,10,1744060584.1769361,15.921221733093262,0.0,1744060584.176937,15.921221733093262,-22627416989.969524,1744060584.1769383,15.921221733093262,0.0,1744060584.1769395,15.921221733093262,28284271247.461903
+1744060584.1969445,15.941232442855835,-7.16608581930581,1744060584.1969461,15.941232442855835,-32.026576259766706,1744060584.1969485,15.941232442855835,0.0,1744060584.1969507,15.941232442855835,56568542496.923805,1744060584.1969519,15.941232442855835,0.0,1744060584.196953,15.941232442855835,5.661552311949913e-10,1744060584.196954,15.941232442855835,32.026576259766706,1744060584.1969552,15.941232442855835,4.611826979911849e-20,1744060584.1969564,15.941232442855835,10,1744060584.1969573,15.941232442855835,0.0,1744060584.1969583,15.941232442855835,-22627416989.969524,1744060584.1969593,15.941232442855835,0.0,1744060584.1969602,15.941232442855835,28284271247.461903
+1744060584.2169755,15.961243629455566,-7.16608581930581,1744060584.2169771,15.961243629455566,-32.026576259766706,1744060584.2169795,15.961243629455566,0.0,1744060584.2169814,15.961243629455566,56568542496.923805,1744060584.2169826,15.961243629455566,0.0,1744060584.2169838,15.961243629455566,5.661552311949913e-10,1744060584.216985,15.961243629455566,32.026576259766706,1744060584.2169862,15.961243629455566,4.611826979911849e-20,1744060584.2169874,15.961243629455566,10,1744060584.216988,15.961243629455566,0.0,1744060584.2169893,15.961243629455566,-22627416989.969524,1744060584.2169902,15.961243629455566,0.0,1744060584.216991,15.961243629455566,28284271247.461903
+1744060584.2378087,15.981334447860718,-7.16608581930581,1744060584.237812,15.981334447860718,-32.026576259766706,1744060584.2378154,15.981334447860718,0.0,1744060584.237818,15.981334447860718,56568542496.923805,1744060584.2378197,15.981334447860718,0.0,1744060584.2378209,15.981334447860718,5.661552311949913e-10,1744060584.2378228,15.981334447860718,32.026576259766706,1744060584.2378242,15.981334447860718,4.611826979911849e-20,1744060584.2378263,15.981334447860718,10,1744060584.2378275,15.981334447860718,0.0,1744060584.237829,15.981334447860718,-22627416989.969524,1744060584.2378306,15.981334447860718,0.0,1744060584.2378316,15.981334447860718,28284271247.461903
+1744060584.257402,16.001259803771973,-7.084594629926196,1744060584.2574036,16.001259803771973,-32.07218940616111,1744060584.257406,16.001259803771973,0.0,1744060584.257408,16.001259803771973,56568542496.923805,1744060584.257409,16.001259803771973,0.0,1744060584.2574103,16.001259803771973,5.669615653238459e-10,1744060584.2574112,16.001259803771973,32.07218940616111,1744060584.2574127,16.001259803771973,4.618395273003822e-20,1744060584.2574136,16.001259803771973,10,1744060584.2574146,16.001259803771973,0.0,1744060584.2574158,16.001259803771973,-22627416989.969524,1744060584.2574165,16.001259803771973,0.0,1744060584.2574174,16.001259803771973,28284271247.461903
+1744060584.276921,16.021242141723633,-7.084594629926196,1744060584.276923,16.021242141723633,-32.07218940616111,1744060584.276925,16.021242141723633,0.0,1744060584.2769272,16.021242141723633,56568542496.923805,1744060584.2769282,16.021242141723633,0.0,1744060584.2769294,16.021242141723633,5.669615653238459e-10,1744060584.2769306,16.021242141723633,32.07218940616111,1744060584.2769318,16.021242141723633,4.618395273003822e-20,1744060584.276933,16.021242141723633,10,1744060584.276934,16.021242141723633,0.0,1744060584.2769346,16.021242141723633,-22627416989.969524,1744060584.2769356,16.021242141723633,0.0,1744060584.2769368,16.021242141723633,28284271247.461903
+1744060584.296985,16.041245222091675,-7.084594629926196,1744060584.2969863,16.041245222091675,-32.07218940616111,1744060584.2969885,16.041245222091675,0.0,1744060584.2969906,16.041245222091675,56568542496.923805,1744060584.2969916,16.041245222091675,0.0,1744060584.2969928,16.041245222091675,5.669615653238459e-10,1744060584.296994,16.041245222091675,32.07218940616111,1744060584.2969952,16.041245222091675,4.618395273003822e-20,1744060584.296996,16.041245222091675,10,1744060584.296997,16.041245222091675,0.0,1744060584.2969983,16.041245222091675,-22627416989.969524,1744060584.296999,16.041245222091675,0.0,1744060584.297,16.041245222091675,28284271247.461903
+1744060584.3172743,16.061234712600708,-7.084594629926196,1744060584.3172762,16.061234712600708,-32.07218940616111,1744060584.3172784,16.061234712600708,0.0,1744060584.3173013,16.061234712600708,56568542496.923805,1744060584.3173022,16.061234712600708,0.0,1744060584.317304,16.061234712600708,5.669615653238459e-10,1744060584.3173048,16.061234712600708,32.07218940616111,1744060584.317306,16.061234712600708,4.618395273003822e-20,1744060584.3173072,16.061234712600708,10,1744060584.3173082,16.061234712600708,0.0,1744060584.3173091,16.061234712600708,-22627416989.969524,1744060584.317329,16.061234712600708,0.0,1744060584.31733,16.061234712600708,28284271247.461903
+1744060584.3369217,16.081225633621216,-7.084594629926196,1744060584.3369234,16.081225633621216,-32.07218940616111,1744060584.3369257,16.081225633621216,0.0,1744060584.3369277,16.081225633621216,56568542496.923805,1744060584.3369288,16.081225633621216,0.0,1744060584.33693,16.081225633621216,5.669615653238459e-10,1744060584.3369312,16.081225633621216,32.07218940616111,1744060584.3369324,16.081225633621216,4.618395273003822e-20,1744060584.3369336,16.081225633621216,10,1744060584.3369343,16.081225633621216,0.0,1744060584.3369355,16.081225633621216,-22627416989.969524,1744060584.3369362,16.081225633621216,0.0,1744060584.3369372,16.081225633621216,28284271247.461903
+1744060584.357553,16.101229190826416,-7.084594629926196,1744060584.3575547,16.101229190826416,-32.07218940616111,1744060584.3575568,16.101229190826416,0.0,1744060584.357559,16.101229190826416,56568542496.923805,1744060584.3575602,16.101229190826416,0.0,1744060584.3575616,16.101229190826416,5.669615653238459e-10,1744060584.3575625,16.101229190826416,32.07218940616111,1744060584.3575637,16.101229190826416,4.618395273003822e-20,1744060584.357565,16.101229190826416,10,1744060584.357566,16.101229190826416,0.0,1744060584.357567,16.101229190826416,-22627416989.969524,1744060584.357568,16.101229190826416,0.0,1744060584.357569,16.101229190826416,28284271247.461903
+1744060584.376926,16.121222496032715,-7.084594629926196,1744060584.3769279,16.121222496032715,-32.07218940616111,1744060584.37693,16.121222496032715,0.0,1744060584.3769321,16.121222496032715,56568542496.923805,1744060584.376933,16.121222496032715,0.0,1744060584.3769343,16.121222496032715,5.669615653238459e-10,1744060584.3769355,16.121222496032715,32.07218940616111,1744060584.3769367,16.121222496032715,4.618395273003822e-20,1744060584.3769376,16.121222496032715,10,1744060584.3769388,16.121222496032715,0.0,1744060584.3769395,16.121222496032715,-22627416989.969524,1744060584.3769405,16.121222496032715,0.0,1744060584.3769417,16.121222496032715,28284271247.461903
+1744060584.3970008,16.141225576400757,-7.084594629926196,1744060584.3970025,16.141225576400757,-32.07218940616111,1744060584.3970048,16.141225576400757,0.0,1744060584.3970068,16.141225576400757,56568542496.923805,1744060584.397008,16.141225576400757,0.0,1744060584.3970091,16.141225576400757,5.669615653238459e-10,1744060584.3970103,16.141225576400757,32.07218940616111,1744060584.3970118,16.141225576400757,4.618395273003822e-20,1744060584.3970127,16.141225576400757,10,1744060584.3970137,16.141225576400757,0.0,1744060584.3970146,16.141225576400757,-22627416989.969524,1744060584.3970156,16.141225576400757,0.0,1744060584.3970165,16.141225576400757,28284271247.461903
+1744060584.4169016,16.161216735839844,-7.084594629926196,1744060584.4169035,16.161216735839844,-32.07218940616111,1744060584.4169056,16.161216735839844,0.0,1744060584.4169078,16.161216735839844,56568542496.923805,1744060584.4169087,16.161216735839844,0.0,1744060584.4169102,16.161216735839844,5.669615653238459e-10,1744060584.4169111,16.161216735839844,32.07218940616111,1744060584.4169123,16.161216735839844,4.618395273003822e-20,1744060584.4169135,16.161216735839844,10,1744060584.4169142,16.161216735839844,0.0,1744060584.4169152,16.161216735839844,-22627416989.969524,1744060584.4169161,16.161216735839844,0.0,1744060584.4169173,16.161216735839844,28284271247.461903
+1744060584.436927,16.181222677230835,-7.084594629926196,1744060584.4369287,16.181222677230835,-32.07218940616111,1744060584.4369311,16.181222677230835,0.0,1744060584.4369333,16.181222677230835,56568542496.923805,1744060584.4369345,16.181222677230835,0.0,1744060584.4369357,16.181222677230835,5.669615653238459e-10,1744060584.4369366,16.181222677230835,32.07218940616111,1744060584.4369378,16.181222677230835,4.618395273003822e-20,1744060584.4369388,16.181222677230835,10,1744060584.4369397,16.181222677230835,0.0,1744060584.436941,16.181222677230835,-22627416989.969524,1744060584.4369416,16.181222677230835,0.0,1744060584.4369426,16.181222677230835,28284271247.461903
+1744060584.4575915,16.201226234436035,-7.084594629926196,1744060584.4575946,16.201226234436035,-32.07218940616111,1744060584.457598,16.201226234436035,0.0,1744060584.457602,16.201226234436035,56568542496.923805,1744060584.4576037,16.201226234436035,0.0,1744060584.4576058,16.201226234436035,5.669615653238459e-10,1744060584.4576075,16.201226234436035,32.07218940616111,1744060584.457609,16.201226234436035,4.618395273003822e-20,1744060584.4576106,16.201226234436035,10,1744060584.4576116,16.201226234436035,0.0,1744060584.4576128,16.201226234436035,-22627416989.969524,1744060584.4576142,16.201226234436035,0.0,1744060584.4576151,16.201226234436035,28284271247.461903
+1744060584.4769673,16.221219062805176,-7.084594629926196,1744060584.4769695,16.221219062805176,-32.07218940616111,1744060584.4769719,16.221219062805176,0.0,1744060584.476974,16.221219062805176,56568542496.923805,1744060584.4769752,16.221219062805176,0.0,1744060584.4769766,16.221219062805176,5.669615653238459e-10,1744060584.4769778,16.221219062805176,32.07218940616111,1744060584.4769793,16.221219062805176,4.618395273003822e-20,1744060584.4769804,16.221219062805176,10,1744060584.4769812,16.221219062805176,0.0,1744060584.4769824,16.221219062805176,-22627416989.969524,1744060584.4769833,16.221219062805176,0.0,1744060584.4769845,16.221219062805176,28284271247.461903
+1744060584.4969382,16.241225242614746,-7.084594629926196,1744060584.4969404,16.241225242614746,-32.07218940616111,1744060584.4969425,16.241225242614746,0.0,1744060584.496945,16.241225242614746,56568542496.923805,1744060584.4969459,16.241225242614746,0.0,1744060584.4969473,16.241225242614746,5.669615653238459e-10,1744060584.4969482,16.241225242614746,32.07218940616111,1744060584.4969492,16.241225242614746,4.618395273003822e-20,1744060584.4969506,16.241225242614746,10,1744060584.4969513,16.241225242614746,0.0,1744060584.4969523,16.241225242614746,-22627416989.969524,1744060584.4969532,16.241225242614746,0.0,1744060584.4969542,16.241225242614746,28284271247.461903
+1744060584.5169034,16.261233806610107,-7.084594629926196,1744060584.5169053,16.261233806610107,-32.07218940616111,1744060584.5169072,16.261233806610107,0.0,1744060584.5169094,16.261233806610107,56568542496.923805,1744060584.51691,16.261233806610107,0.0,1744060584.5169113,16.261233806610107,5.669615653238459e-10,1744060584.5169127,16.261233806610107,32.07218940616111,1744060584.5169137,16.261233806610107,4.618395273003822e-20,1744060584.5169146,16.261233806610107,10,1744060584.5169158,16.261233806610107,0.0,1744060584.5169165,16.261233806610107,-22627416989.969524,1744060584.5169175,16.261233806610107,0.0,1744060584.5169184,16.261233806610107,28284271247.461903
+1744060584.5369458,16.281259059906006,-7.084594629926196,1744060584.5369477,16.281259059906006,-32.07218940616111,1744060584.53695,16.281259059906006,0.0,1744060584.536952,16.281259059906006,56568542496.923805,1744060584.536953,16.281259059906006,0.0,1744060584.5369544,16.281259059906006,5.669615653238459e-10,1744060584.5369556,16.281259059906006,32.07218940616111,1744060584.5369568,16.281259059906006,4.618395273003822e-20,1744060584.536958,16.281259059906006,10,1744060584.5369587,16.281259059906006,0.0,1744060584.53696,16.281259059906006,-22627416989.969524,1744060584.536961,16.281259059906006,0.0,1744060584.536962,16.281259059906006,28284271247.461903
+1744060584.558048,16.301257610321045,-7.084594629926196,1744060584.5580504,16.301257610321045,-32.07218940616111,1744060584.558053,16.301257610321045,0.0,1744060584.5580554,16.301257610321045,56568542496.923805,1744060584.5580564,16.301257610321045,0.0,1744060584.558058,16.301257610321045,5.669615653238459e-10,1744060584.5580592,16.301257610321045,32.07218940616111,1744060584.5580606,16.301257610321045,4.618395273003822e-20,1744060584.5580618,16.301257610321045,10,1744060584.5580635,16.301257610321045,0.0,1744060584.558065,16.301257610321045,-22627416989.969524,1744060584.558066,16.301257610321045,0.0,1744060584.5580676,16.301257610321045,28284271247.461903
+1744060584.5769827,16.32125687599182,-7.084594629926196,1744060584.5769846,16.32125687599182,-32.07218940616111,1744060584.576987,16.32125687599182,0.0,1744060584.5769892,16.32125687599182,56568542496.923805,1744060584.5769901,16.32125687599182,0.0,1744060584.5769916,16.32125687599182,5.669615653238459e-10,1744060584.5769928,16.32125687599182,32.07218940616111,1744060584.5769937,16.32125687599182,4.618395273003822e-20,1744060584.5769951,16.32125687599182,10,1744060584.576996,16.32125687599182,0.0,1744060584.5769968,16.32125687599182,-22627416989.969524,1744060584.576998,16.32125687599182,0.0,1744060584.576999,16.32125687599182,28284271247.461903
+1744060584.597026,16.341257333755493,-7.084594629926196,1744060584.5970278,16.341257333755493,-32.07218940616111,1744060584.5970302,16.341257333755493,0.0,1744060584.5970323,16.341257333755493,56568542496.923805,1744060584.5970333,16.341257333755493,0.0,1744060584.5970342,16.341257333755493,5.669615653238459e-10,1744060584.5970354,16.341257333755493,32.07218940616111,1744060584.5970366,16.341257333755493,4.618395273003822e-20,1744060584.5970378,16.341257333755493,10,1744060584.5970385,16.341257333755493,0.0,1744060584.5970397,16.341257333755493,-22627416989.969524,1744060584.5970407,16.341257333755493,0.0,1744060584.5970414,16.341257333755493,28284271247.461903
+1744060584.6171806,16.361225128173828,-7.084594629926196,1744060584.6171827,16.361225128173828,-32.07218940616111,1744060584.6171854,16.361225128173828,0.0,1744060584.6171875,16.361225128173828,56568542496.923805,1744060584.6171887,16.361225128173828,0.0,1744060584.6171896,16.361225128173828,5.669615653238459e-10,1744060584.6171908,16.361225128173828,32.07218940616111,1744060584.617192,16.361225128173828,4.618395273003822e-20,1744060584.6171935,16.361225128173828,10,1744060584.6171944,16.361225128173828,0.0,1744060584.6171956,16.361225128173828,-22627416989.969524,1744060584.6171966,16.361225128173828,0.0,1744060584.6171975,16.361225128173828,28284271247.461903
+1744060584.6370873,16.38122010231018,-7.084594629926196,1744060584.637089,16.38122010231018,-32.07218940616111,1744060584.6370914,16.38122010231018,0.0,1744060584.6370933,16.38122010231018,56568542496.923805,1744060584.6370947,16.38122010231018,0.0,1744060584.637096,16.38122010231018,5.669615653238459e-10,1744060584.637097,16.38122010231018,32.07218940616111,1744060584.637098,16.38122010231018,4.618395273003822e-20,1744060584.637099,16.38122010231018,10,1744060584.6371,16.38122010231018,0.0,1744060584.6371012,16.38122010231018,-22627416989.969524,1744060584.6371021,16.38122010231018,0.0,1744060584.6371028,16.38122010231018,28284271247.461903
+1744060584.657359,16.40125846862793,-7.084594629926196,1744060584.6573608,16.40125846862793,-32.07218940616111,1744060584.657363,16.40125846862793,0.0,1744060584.6573653,16.40125846862793,56568542496.923805,1744060584.6573663,16.40125846862793,0.0,1744060584.6573675,16.40125846862793,5.669615653238459e-10,1744060584.6573687,16.40125846862793,32.07218940616111,1744060584.6573696,16.40125846862793,4.618395273003822e-20,1744060584.657371,16.40125846862793,10,1744060584.6573725,16.40125846862793,0.0,1744060584.6573734,16.40125846862793,-22627416989.969524,1744060584.6573744,16.40125846862793,0.0,1744060584.6573753,16.40125846862793,28284271247.461903
+1744060584.6769044,16.421218395233154,-7.084594629926196,1744060584.6769066,16.421218395233154,-32.07218940616111,1744060584.6769085,16.421218395233154,0.0,1744060584.6769109,16.421218395233154,56568542496.923805,1744060584.6769118,16.421218395233154,0.0,1744060584.6769128,16.421218395233154,5.669615653238459e-10,1744060584.6769142,16.421218395233154,32.07218940616111,1744060584.6769152,16.421218395233154,4.618395273003822e-20,1744060584.6769161,16.421218395233154,10,1744060584.6769173,16.421218395233154,0.0,1744060584.6769183,16.421218395233154,-22627416989.969524,1744060584.6769192,16.421218395233154,0.0,1744060584.6769202,16.421218395233154,28284271247.461903
+1744060584.6977468,16.441283702850342,-7.084594629926196,1744060584.697749,16.441283702850342,-32.07218940616111,1744060584.6977515,16.441283702850342,0.0,1744060584.6977544,16.441283702850342,56568542496.923805,1744060584.6977553,16.441283702850342,0.0,1744060584.697757,16.441283702850342,5.669615653238459e-10,1744060584.6977584,16.441283702850342,32.07218940616111,1744060584.69776,16.441283702850342,4.618395273003822e-20,1744060584.697761,16.441283702850342,10,1744060584.6977627,16.441283702850342,0.0,1744060584.697764,16.441283702850342,-22627416989.969524,1744060584.697765,16.441283702850342,0.0,1744060584.6977663,16.441283702850342,28284271247.461903
+1744060584.7169502,16.461250066757202,-7.084594629926196,1744060584.7169526,16.461250066757202,-32.07218940616111,1744060584.716955,16.461250066757202,0.0,1744060584.7169569,16.461250066757202,56568542496.923805,1744060584.716958,16.461250066757202,0.0,1744060584.7169592,16.461250066757202,5.669615653238459e-10,1744060584.7169602,16.461250066757202,32.07218940616111,1744060584.7169616,16.461250066757202,4.618395273003822e-20,1744060584.7169626,16.461250066757202,10,1744060584.7169635,16.461250066757202,0.0,1744060584.7169647,16.461250066757202,-22627416989.969524,1744060584.7169654,16.461250066757202,0.0,1744060584.7169664,16.461250066757202,28284271247.461903
+1744060584.7369492,16.48120355606079,-7.084594629926196,1744060584.736951,16.48120355606079,-32.07218940616111,1744060584.7369533,16.48120355606079,0.0,1744060584.7369552,16.48120355606079,56568542496.923805,1744060584.7369561,16.48120355606079,0.0,1744060584.7369576,16.48120355606079,5.669615653238459e-10,1744060584.7369587,16.48120355606079,32.07218940616111,1744060584.73696,16.48120355606079,4.618395273003822e-20,1744060584.7369614,16.48120355606079,10,1744060584.7369623,16.48120355606079,0.0,1744060584.7369633,16.48120355606079,-22627416989.969524,1744060584.736964,16.48120355606079,0.0,1744060584.7369652,16.48120355606079,28284271247.461903
+1744060584.7571614,16.501218795776367,-7.024599259866761,1744060584.7571633,16.501218795776367,-32.09241875153066,1744060584.7571652,16.501218795776367,0.0,1744060584.7571676,16.501218795776367,56568542496.923805,1744060584.7571683,16.501218795776367,0.0,1744060584.7571697,16.501218795776367,5.673191730066344e-10,1744060584.7571707,16.501218795776367,32.09241875153066,1744060584.7571719,16.501218795776367,4.621308298745904e-20,1744060584.7571733,16.501218795776367,10,1744060584.7571743,16.501218795776367,0.0,1744060584.7571752,16.501218795776367,-22627416989.969524,1744060584.7571762,16.501218795776367,0.0,1744060584.757177,16.501218795776367,28284271247.461903
+1744060584.7770326,16.52125644683838,-7.024599259866761,1744060584.7770345,16.52125644683838,-32.09241875153066,1744060584.777037,16.52125644683838,0.0,1744060584.777039,16.52125644683838,56568542496.923805,1744060584.7770402,16.52125644683838,0.0,1744060584.7770414,16.52125644683838,5.673191730066344e-10,1744060584.7770424,16.52125644683838,32.09241875153066,1744060584.777044,16.52125644683838,4.621308298745904e-20,1744060584.7770452,16.52125644683838,10,1744060584.7770464,16.52125644683838,0.0,1744060584.7770476,16.52125644683838,-22627416989.969524,1744060584.7770486,16.52125644683838,0.0,1744060584.7770498,16.52125644683838,28284271247.461903
+1744060584.7969837,16.541229963302612,-7.024599259866761,1744060584.7969863,16.541229963302612,-32.09241875153066,1744060584.7969897,16.541229963302612,0.0,1744060584.7969935,16.541229963302612,56568542496.923805,1744060584.7969956,16.541229963302612,0.0,1744060584.7969983,16.541229963302612,5.673191730066344e-10,1744060584.7970002,16.541229963302612,32.09241875153066,1744060584.7970023,16.541229963302612,4.621308298745904e-20,1744060584.7970042,16.541229963302612,10,1744060584.7970064,16.541229963302612,0.0,1744060584.797008,16.541229963302612,-22627416989.969524,1744060584.79701,16.541229963302612,0.0,1744060584.7970119,16.541229963302612,28284271247.461903
+1744060584.8168926,16.561217308044434,-7.024599259866761,1744060584.8168945,16.561217308044434,-32.09241875153066,1744060584.8168967,16.561217308044434,0.0,1744060584.8168988,16.561217308044434,56568542496.923805,1744060584.8168998,16.561217308044434,0.0,1744060584.816901,16.561217308044434,5.673191730066344e-10,1744060584.8169022,16.561217308044434,32.09241875153066,1744060584.816903,16.561217308044434,4.621308298745904e-20,1744060584.8169045,16.561217308044434,10,1744060584.8169057,16.561217308044434,0.0,1744060584.8169072,16.561217308044434,-22627416989.969524,1744060584.8169088,16.561217308044434,0.0,1744060584.8169103,16.561217308044434,28284271247.461903
+1744060584.8370373,16.581278085708618,-7.024599259866761,1744060584.837039,16.581278085708618,-32.09241875153066,1744060584.8370411,16.581278085708618,0.0,1744060584.8370435,16.581278085708618,56568542496.923805,1744060584.8370442,16.581278085708618,0.0,1744060584.8370454,16.581278085708618,5.673191730066344e-10,1744060584.8370466,16.581278085708618,32.09241875153066,1744060584.8370478,16.581278085708618,4.621308298745904e-20,1744060584.8370488,16.581278085708618,10,1744060584.83705,16.581278085708618,0.0,1744060584.8370507,16.581278085708618,-22627416989.969524,1744060584.8370516,16.581278085708618,0.0,1744060584.8370526,16.581278085708618,28284271247.461903
+1744060584.8572183,16.601220846176147,-7.024599259866761,1744060584.8572202,16.601220846176147,-32.09241875153066,1744060584.857222,16.601220846176147,0.0,1744060584.8572242,16.601220846176147,56568542496.923805,1744060584.8572252,16.601220846176147,0.0,1744060584.8572266,16.601220846176147,5.673191730066344e-10,1744060584.857228,16.601220846176147,32.09241875153066,1744060584.857229,16.601220846176147,4.621308298745904e-20,1744060584.8572304,16.601220846176147,10,1744060584.8572314,16.601220846176147,0.0,1744060584.857232,16.601220846176147,-22627416989.969524,1744060584.857233,16.601220846176147,0.0,1744060584.8572342,16.601220846176147,28284271247.461903
+1744060584.8770142,16.621253728866577,-7.024599259866761,1744060584.8770158,16.621253728866577,-32.09241875153066,1744060584.8770182,16.621253728866577,0.0,1744060584.8770201,16.621253728866577,56568542496.923805,1744060584.877021,16.621253728866577,0.0,1744060584.8770223,16.621253728866577,5.673191730066344e-10,1744060584.8770235,16.621253728866577,32.09241875153066,1744060584.8770247,16.621253728866577,4.621308298745904e-20,1744060584.877026,16.621253728866577,10,1744060584.8770268,16.621253728866577,0.0,1744060584.8770278,16.621253728866577,-22627416989.969524,1744060584.877029,16.621253728866577,0.0,1744060584.87703,16.621253728866577,28284271247.461903
+1744060584.896991,16.64126443862915,-7.024599259866761,1744060584.8969927,16.64126443862915,-32.09241875153066,1744060584.896995,16.64126443862915,0.0,1744060584.8969975,16.64126443862915,56568542496.923805,1744060584.8969984,16.64126443862915,0.0,1744060584.8969996,16.64126443862915,5.673191730066344e-10,1744060584.897001,16.64126443862915,32.09241875153066,1744060584.897002,16.64126443862915,4.621308298745904e-20,1744060584.8970032,16.64126443862915,10,1744060584.8970044,16.64126443862915,0.0,1744060584.897005,16.64126443862915,-22627416989.969524,1744060584.897006,16.64126443862915,0.0,1744060584.897007,16.64126443862915,28284271247.461903
+1744060584.9171028,16.661268711090088,-7.024599259866761,1744060584.9171057,16.661268711090088,-32.09241875153066,1744060584.917109,16.661268711090088,0.0,1744060584.9171119,16.661268711090088,56568542496.923805,1744060584.9171133,16.661268711090088,0.0,1744060584.9171147,16.661268711090088,5.673191730066344e-10,1744060584.9171162,16.661268711090088,32.09241875153066,1744060584.9171183,16.661268711090088,4.621308298745904e-20,1744060584.9171193,16.661268711090088,10,1744060584.9171207,16.661268711090088,0.0,1744060584.9171221,16.661268711090088,-22627416989.969524,1744060584.917123,16.661268711090088,0.0,1744060584.9171245,16.661268711090088,28284271247.461903
+1744060584.9369898,16.6812641620636,-7.024599259866761,1744060584.9369915,16.6812641620636,-32.09241875153066,1744060584.9369936,16.6812641620636,0.0,1744060584.9369955,16.6812641620636,56568542496.923805,1744060584.9369967,16.6812641620636,0.0,1744060584.936998,16.6812641620636,5.673191730066344e-10,1744060584.936999,16.6812641620636,32.09241875153066,1744060584.9370003,16.6812641620636,4.621308298745904e-20,1744060584.9370015,16.6812641620636,10,1744060584.9370022,16.6812641620636,0.0,1744060584.9370034,16.6812641620636,-22627416989.969524,1744060584.9370043,16.6812641620636,0.0,1744060584.937005,16.6812641620636,28284271247.461903
+1744060584.9571428,16.701217889785767,-7.024599259866761,1744060584.9571445,16.701217889785767,-32.09241875153066,1744060584.9571638,16.701217889785767,0.0,1744060584.9571657,16.701217889785767,56568542496.923805,1744060584.9571667,16.701217889785767,0.0,1744060584.9571679,16.701217889785767,5.673191730066344e-10,1744060584.957169,16.701217889785767,32.09241875153066,1744060584.9571705,16.701217889785767,4.621308298745904e-20,1744060584.957188,16.701217889785767,10,1744060584.957189,16.701217889785767,0.0,1744060584.95719,16.701217889785767,-22627416989.969524,1744060584.9571912,16.701217889785767,0.0,1744060584.957192,16.701217889785767,28284271247.461903
+1744060584.977036,16.721221446990967,-7.024599259866761,1744060584.9770377,16.721221446990967,-32.09241875153066,1744060584.9770398,16.721221446990967,0.0,1744060584.977042,16.721221446990967,56568542496.923805,1744060584.977043,16.721221446990967,0.0,1744060584.9770439,16.721221446990967,5.673191730066344e-10,1744060584.9770453,16.721221446990967,32.09241875153066,1744060584.9770465,16.721221446990967,4.621308298745904e-20,1744060584.977048,16.721221446990967,10,1744060584.9770489,16.721221446990967,0.0,1744060584.9770498,16.721221446990967,-22627416989.969524,1744060584.9770505,16.721221446990967,0.0,1744060584.9770517,16.721221446990967,28284271247.461903
+1744060584.9970803,16.741225481033325,-7.024599259866761,1744060584.997082,16.741225481033325,-32.09241875153066,1744060584.9970844,16.741225481033325,0.0,1744060584.9970868,16.741225481033325,56568542496.923805,1744060584.9970875,16.741225481033325,0.0,1744060584.9970887,16.741225481033325,5.673191730066344e-10,1744060584.9970899,16.741225481033325,32.09241875153066,1744060584.997091,16.741225481033325,4.621308298745904e-20,1744060584.9970922,16.741225481033325,10,1744060584.9970934,16.741225481033325,0.0,1744060584.9970942,16.741225481033325,-22627416989.969524,1744060584.997095,16.741225481033325,0.0,1744060584.9970963,16.741225481033325,28284271247.461903
+1744060585.0171232,16.761295080184937,-7.024599259866761,1744060585.0171254,16.761295080184937,-32.09241875153066,1744060585.0171278,16.761295080184937,0.0,1744060585.0171297,16.761295080184937,56568542496.923805,1744060585.0171309,16.761295080184937,0.0,1744060585.0171318,16.761295080184937,5.673191730066344e-10,1744060585.017133,16.761295080184937,32.09241875153066,1744060585.0171342,16.761295080184937,4.621308298745904e-20,1744060585.0171354,16.761295080184937,10,1744060585.017136,16.761295080184937,0.0,1744060585.017137,16.761295080184937,-22627416989.969524,1744060585.0171382,16.761295080184937,0.0,1744060585.0171392,16.761295080184937,28284271247.461903
+1744060585.0372572,16.78131103515625,-7.024599259866761,1744060585.037259,16.78131103515625,-32.09241875153066,1744060585.0372612,16.78131103515625,0.0,1744060585.0372634,16.78131103515625,56568542496.923805,1744060585.0372643,16.78131103515625,0.0,1744060585.0372653,16.78131103515625,5.673191730066344e-10,1744060585.0372667,16.78131103515625,32.09241875153066,1744060585.037268,16.78131103515625,4.621308298745904e-20,1744060585.0372689,16.78131103515625,10,1744060585.03727,16.78131103515625,0.0,1744060585.037271,16.78131103515625,-22627416989.969524,1744060585.037272,16.78131103515625,0.0,1744060585.037273,16.78131103515625,28284271247.461903
+1744060585.0576231,16.801253080368042,-7.024599259866761,1744060585.057625,16.801253080368042,-32.09241875153066,1744060585.0576272,16.801253080368042,0.0,1744060585.057629,16.801253080368042,56568542496.923805,1744060585.0576305,16.801253080368042,0.0,1744060585.0576315,16.801253080368042,5.673191730066344e-10,1744060585.0576327,16.801253080368042,32.09241875153066,1744060585.0576339,16.801253080368042,4.621308298745904e-20,1744060585.057635,16.801253080368042,10,1744060585.057636,16.801253080368042,0.0,1744060585.057637,16.801253080368042,-22627416989.969524,1744060585.057638,16.801253080368042,0.0,1744060585.0576386,16.801253080368042,28284271247.461903
+1744060585.076925,16.821224212646484,-7.024599259866761,1744060585.0769267,16.821224212646484,-32.09241875153066,1744060585.0769289,16.821224212646484,0.0,1744060585.076931,16.821224212646484,56568542496.923805,1744060585.076932,16.821224212646484,0.0,1744060585.0769331,16.821224212646484,5.673191730066344e-10,1744060585.0769343,16.821224212646484,32.09241875153066,1744060585.0769355,16.821224212646484,4.621308298745904e-20,1744060585.0769367,16.821224212646484,10,1744060585.0769374,16.821224212646484,0.0,1744060585.0769384,16.821224212646484,-22627416989.969524,1744060585.0769396,16.821224212646484,0.0,1744060585.0769405,16.821224212646484,28284271247.461903
+1744060585.0969148,16.841217756271362,-7.024599259866761,1744060585.0969164,16.841217756271362,-32.09241875153066,1744060585.0969188,16.841217756271362,0.0,1744060585.0969207,16.841217756271362,56568542496.923805,1744060585.096922,16.841217756271362,0.0,1744060585.0969229,16.841217756271362,5.673191730066344e-10,1744060585.096924,16.841217756271362,32.09241875153066,1744060585.0969253,16.841217756271362,4.621308298745904e-20,1744060585.0969262,16.841217756271362,10,1744060585.0969272,16.841217756271362,0.0,1744060585.096928,16.841217756271362,-22627416989.969524,1744060585.096929,16.841217756271362,0.0,1744060585.09693,16.841217756271362,28284271247.461903
+1744060585.1174734,16.861218452453613,-7.024599259866761,1744060585.1174753,16.861218452453613,-32.09241875153066,1744060585.1174777,16.861218452453613,0.0,1744060585.1174796,16.861218452453613,56568542496.923805,1744060585.1174808,16.861218452453613,0.0,1744060585.117482,16.861218452453613,5.673191730066344e-10,1744060585.117483,16.861218452453613,32.09241875153066,1744060585.117484,16.861218452453613,4.621308298745904e-20,1744060585.117485,16.861218452453613,10,1744060585.117486,16.861218452453613,0.0,1744060585.117487,16.861218452453613,-22627416989.969524,1744060585.117488,16.861218452453613,0.0,1744060585.1174889,16.861218452453613,28284271247.461903
+1744060585.1369636,16.881272315979004,-7.024599259866761,1744060585.1369655,16.881272315979004,-32.09241875153066,1744060585.1369677,16.881272315979004,0.0,1744060585.1369698,16.881272315979004,56568542496.923805,1744060585.1369708,16.881272315979004,0.0,1744060585.136972,16.881272315979004,5.673191730066344e-10,1744060585.1369731,16.881272315979004,32.09241875153066,1744060585.1369743,16.881272315979004,4.621308298745904e-20,1744060585.1369753,16.881272315979004,10,1744060585.1369765,16.881272315979004,0.0,1744060585.1369834,16.881272315979004,-22627416989.969524,1744060585.1369843,16.881272315979004,0.0,1744060585.1369853,16.881272315979004,28284271247.461903
+1744060585.1575153,16.901233196258545,-7.024599259866761,1744060585.1575172,16.901233196258545,-32.09241875153066,1744060585.1575198,16.901233196258545,0.0,1744060585.157522,16.901233196258545,56568542496.923805,1744060585.157523,16.901233196258545,0.0,1744060585.1575239,16.901233196258545,5.673191730066344e-10,1744060585.1575253,16.901233196258545,32.09241875153066,1744060585.1575263,16.901233196258545,4.621308298745904e-20,1744060585.1575272,16.901233196258545,10,1744060585.1575286,16.901233196258545,0.0,1744060585.1575294,16.901233196258545,-22627416989.969524,1744060585.1575303,16.901233196258545,0.0,1744060585.157531,16.901233196258545,28284271247.461903
+1744060585.1768823,16.921216249465942,-7.024599259866761,1744060585.176884,16.921216249465942,-32.09241875153066,1744060585.1768863,16.921216249465942,0.0,1744060585.1768882,16.921216249465942,56568542496.923805,1744060585.1768894,16.921216249465942,0.0,1744060585.1768904,16.921216249465942,5.673191730066344e-10,1744060585.1768916,16.921216249465942,32.09241875153066,1744060585.1768928,16.921216249465942,4.621308298745904e-20,1744060585.176894,16.921216249465942,10,1744060585.1768947,16.921216249465942,0.0,1744060585.1768959,16.921216249465942,-22627416989.969524,1744060585.1768968,16.921216249465942,0.0,1744060585.1768978,16.921216249465942,28284271247.461903
+1744060585.1969898,16.941253423690796,-7.024599259866761,1744060585.1969914,16.941253423690796,-32.09241875153066,1744060585.1969936,16.941253423690796,0.0,1744060585.1969957,16.941253423690796,56568542496.923805,1744060585.1969967,16.941253423690796,0.0,1744060585.196998,16.941253423690796,5.673191730066344e-10,1744060585.1969988,16.941253423690796,32.09241875153066,1744060585.1970003,16.941253423690796,4.621308298745904e-20,1744060585.1970012,16.941253423690796,10,1744060585.1970024,16.941253423690796,0.0,1744060585.1970034,16.941253423690796,-22627416989.969524,1744060585.1970046,16.941253423690796,0.0,1744060585.1970053,16.941253423690796,28284271247.461903
+1744060585.2170181,16.96129584312439,-7.024599259866761,1744060585.2170203,16.96129584312439,-32.09241875153066,1744060585.2170224,16.96129584312439,0.0,1744060585.2170246,16.96129584312439,56568542496.923805,1744060585.2170255,16.96129584312439,0.0,1744060585.2170267,16.96129584312439,5.673191730066344e-10,1744060585.217028,16.96129584312439,32.09241875153066,1744060585.217029,16.96129584312439,4.621308298745904e-20,1744060585.21703,16.96129584312439,10,1744060585.217031,16.96129584312439,0.0,1744060585.217032,16.96129584312439,-22627416989.969524,1744060585.217033,16.96129584312439,0.0,1744060585.217034,16.96129584312439,28284271247.461903
+1744060585.2369246,16.98123574256897,-7.024599259866761,1744060585.2369268,16.98123574256897,-32.09241875153066,1744060585.2369287,16.98123574256897,0.0,1744060585.2369306,16.98123574256897,56568542496.923805,1744060585.2369316,16.98123574256897,0.0,1744060585.2369328,16.98123574256897,5.673191730066344e-10,1744060585.236934,16.98123574256897,32.09241875153066,1744060585.2369351,16.98123574256897,4.621308298745904e-20,1744060585.236936,16.98123574256897,10,1744060585.2369373,16.98123574256897,0.0,1744060585.2369382,16.98123574256897,-22627416989.969524,1744060585.2369392,16.98123574256897,0.0,1744060585.2369404,16.98123574256897,28284271247.461903
+1744060585.257484,17.001219987869263,-6.981248496690771,1744060585.257486,17.001219987869263,-32.09249335911028,1744060585.2574887,17.001219987869263,0.0,1744060585.2574906,17.001219987869263,56568542496.923805,1744060585.2574918,17.001219987869263,0.0,1744060585.257493,17.001219987869263,5.673204918952059e-10,1744060585.2574944,17.001219987869263,32.09249335911028,1744060585.2574959,17.001219987869263,4.621319042244449e-20,1744060585.257497,17.001219987869263,10,1744060585.257498,17.001219987869263,0.0,1744060585.2574992,17.001219987869263,-22627416989.969524,1744060585.2575002,17.001219987869263,0.0,1744060585.2575011,17.001219987869263,28284271247.461903
+1744060585.2769997,17.021228075027466,-6.981248496690771,1744060585.2770014,17.021228075027466,-32.09249335911028,1744060585.2770038,17.021228075027466,0.0,1744060585.2770061,17.021228075027466,56568542496.923805,1744060585.277007,17.021228075027466,0.0,1744060585.2770083,17.021228075027466,5.673204918952059e-10,1744060585.2770097,17.021228075027466,32.09249335911028,1744060585.2770107,17.021228075027466,4.621319042244449e-20,1744060585.2770119,17.021228075027466,10,1744060585.2770128,17.021228075027466,0.0,1744060585.2770138,17.021228075027466,-22627416989.969524,1744060585.2770147,17.021228075027466,0.0,1744060585.277016,17.021228075027466,28284271247.461903
+1744060585.2970955,17.04124402999878,-6.981248496690771,1744060585.2970972,17.04124402999878,-32.09249335911028,1744060585.2970996,17.04124402999878,0.0,1744060585.2971015,17.04124402999878,56568542496.923805,1744060585.2971025,17.04124402999878,0.0,1744060585.2971036,17.04124402999878,5.673204918952059e-10,1744060585.2971046,17.04124402999878,32.09249335911028,1744060585.297106,17.04124402999878,4.621319042244449e-20,1744060585.297107,17.04124402999878,10,1744060585.297108,17.04124402999878,0.0,1744060585.297109,17.04124402999878,-22627416989.969524,1744060585.2971098,17.04124402999878,0.0,1744060585.2971108,17.04124402999878,28284271247.461903
+1744060585.3173876,17.06126642227173,-6.981248496690771,1744060585.3173895,17.06126642227173,-32.09249335911028,1744060585.3173919,17.06126642227173,0.0,1744060585.317394,17.06126642227173,56568542496.923805,1744060585.3173952,17.06126642227173,0.0,1744060585.3174167,17.06126642227173,5.673204918952059e-10,1744060585.317418,17.06126642227173,32.09249335911028,1744060585.317419,17.06126642227173,4.621319042244449e-20,1744060585.3174202,17.06126642227173,10,1744060585.3174212,17.06126642227173,0.0,1744060585.3174222,17.06126642227173,-22627416989.969524,1744060585.317423,17.06126642227173,0.0,1744060585.317424,17.06126642227173,28284271247.461903
+1744060585.3369787,17.081227779388428,-6.981248496690771,1744060585.3369806,17.081227779388428,-32.09249335911028,1744060585.3369825,17.081227779388428,0.0,1744060585.3369849,17.081227779388428,56568542496.923805,1744060585.3369858,17.081227779388428,0.0,1744060585.336987,17.081227779388428,5.673204918952059e-10,1744060585.3369884,17.081227779388428,32.09249335911028,1744060585.3369894,17.081227779388428,4.621319042244449e-20,1744060585.3369908,17.081227779388428,10,1744060585.3369918,17.081227779388428,0.0,1744060585.3369927,17.081227779388428,-22627416989.969524,1744060585.3369935,17.081227779388428,0.0,1744060585.3369946,17.081227779388428,28284271247.461903
+1744060585.3588462,17.10165047645569,-6.981248496690771,1744060585.3588483,17.10165047645569,-32.09249335911028,1744060585.3588507,17.10165047645569,0.0,1744060585.3588533,17.10165047645569,56568542496.923805,1744060585.3588543,17.10165047645569,0.0,1744060585.3588562,17.10165047645569,5.673204918952059e-10,1744060585.3588574,17.10165047645569,32.09249335911028,1744060585.3588588,17.10165047645569,4.621319042244449e-20,1744060585.35886,17.10165047645569,10,1744060585.3588617,17.10165047645569,0.0,1744060585.3588629,17.10165047645569,-22627416989.969524,1744060585.3588643,17.10165047645569,0.0,1744060585.3588681,17.10165047645569,28284271247.461903
+1744060585.3769722,17.121254920959473,-6.981248496690771,1744060585.3769746,17.121254920959473,-32.09249335911028,1744060585.3769767,17.121254920959473,0.0,1744060585.376979,17.121254920959473,56568542496.923805,1744060585.3769803,17.121254920959473,0.0,1744060585.3769815,17.121254920959473,5.673204918952059e-10,1744060585.3769825,17.121254920959473,32.09249335911028,1744060585.376984,17.121254920959473,4.621319042244449e-20,1744060585.376985,17.121254920959473,10,1744060585.376986,17.121254920959473,0.0,1744060585.3769872,17.121254920959473,-22627416989.969524,1744060585.3769882,17.121254920959473,0.0,1744060585.3769891,17.121254920959473,28284271247.461903
+1744060585.3969972,17.141222715377808,-6.981248496690771,1744060585.396999,17.141222715377808,-32.09249335911028,1744060585.397001,17.141222715377808,0.0,1744060585.397003,17.141222715377808,56568542496.923805,1744060585.3970041,17.141222715377808,0.0,1744060585.3970053,17.141222715377808,5.673204918952059e-10,1744060585.3970065,17.141222715377808,32.09249335911028,1744060585.397008,17.141222715377808,4.621319042244449e-20,1744060585.397009,17.141222715377808,10,1744060585.3970098,17.141222715377808,0.0,1744060585.397011,17.141222715377808,-22627416989.969524,1744060585.397012,17.141222715377808,0.0,1744060585.397013,17.141222715377808,28284271247.461903
+1744060585.4169464,17.16122531890869,-6.981248496690771,1744060585.4169483,17.16122531890869,-32.09249335911028,1744060585.4169502,17.16122531890869,0.0,1744060585.4169526,17.16122531890869,56568542496.923805,1744060585.4169536,17.16122531890869,0.0,1744060585.4169545,17.16122531890869,5.673204918952059e-10,1744060585.416956,17.16122531890869,32.09249335911028,1744060585.416957,17.16122531890869,4.621319042244449e-20,1744060585.4169579,17.16122531890869,10,1744060585.416959,17.16122531890869,0.0,1744060585.4169598,17.16122531890869,-22627416989.969524,1744060585.4169607,17.16122531890869,0.0,1744060585.416962,17.16122531890869,28284271247.461903
+1744060585.4368937,17.18121886253357,-6.981248496690771,1744060585.4368954,17.18121886253357,-32.09249335911028,1744060585.4368975,17.18121886253357,0.0,1744060585.4368997,17.18121886253357,56568542496.923805,1744060585.4369006,17.18121886253357,0.0,1744060585.4369016,17.18121886253357,5.673204918952059e-10,1744060585.4369028,17.18121886253357,32.09249335911028,1744060585.436904,17.18121886253357,4.621319042244449e-20,1744060585.436905,17.18121886253357,10,1744060585.436906,17.18121886253357,0.0,1744060585.4369068,17.18121886253357,-22627416989.969524,1744060585.4369078,17.18121886253357,0.0,1744060585.4369087,17.18121886253357,28284271247.461903
+1744060585.4577782,17.201250076293945,-6.981248496690771,1744060585.45778,17.201250076293945,-32.09249335911028,1744060585.4577823,17.201250076293945,0.0,1744060585.4577847,17.201250076293945,56568542496.923805,1744060585.4577856,17.201250076293945,0.0,1744060585.457787,17.201250076293945,5.673204918952059e-10,1744060585.4577885,17.201250076293945,32.09249335911028,1744060585.4577897,17.201250076293945,4.621319042244449e-20,1744060585.457791,17.201250076293945,10,1744060585.457792,17.201250076293945,0.0,1744060585.457793,17.201250076293945,-22627416989.969524,1744060585.457794,17.201250076293945,0.0,1744060585.4577951,17.201250076293945,28284271247.461903
diff --git a/testing/racing_logs/launch_control/behavior.json b/testing/racing_logs/launch_control/behavior.json
new file mode 100644
index 000000000..cadc49715
--- /dev/null
+++ b/testing/racing_logs/launch_control/behavior.json
@@ -0,0 +1,1030 @@
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060568.2563446, "x": -88.23520837493102, "y": 40.09285009483353, "z": 199.51119375252705, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060568.2552168}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.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": 1744060568.2552168}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060568.356478, "x": -88.23520837493102, "y": 40.09285009483353, "z": 199.51119375252705, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060568.3563824}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.3563824}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.3764472}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.3964887}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.4165237}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.4366167}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060568.457236, "x": -88.23520837493102, "y": 40.09285009483353, "z": 199.51119375252705, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060568.4566197}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.4566197}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.476479}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.4965038}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.5164857}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.5365012}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060568.5567353, "x": -88.23520837493102, "y": 40.09285009483353, "z": 199.51119375252705, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060568.556502}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.556502}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.5764542}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.5964766}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.6167443}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.636942}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060568.657337, "x": -88.23520837493102, "y": 40.09285009483353, "z": 199.51119375252705, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060568.6565554}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.6565554}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.6765022}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.6964908}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.716457}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.736825}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060568.7566395, "x": -88.23520836643694, "y": 40.09285011755513, "z": 199.50478182422617, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060568.7564812}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.7564812}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.7765431}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.883796457968402e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.796463}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.883796457968402e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.816459}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.883796457968402e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.8365507}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060568.857667, "x": -88.23520836643694, "y": 40.09285011755513, "z": 199.50478182422617, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060568.8564813}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.883796457968402e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.8564813}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.883796457968402e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.8764977}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.883796457968402e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.896507}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.883796457968402e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.916461}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.883796457968402e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.936487}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060568.956597, "x": -88.23520836643694, "y": 40.09285011755513, "z": 199.50478182422617, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060568.9564571}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.883796457968402e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.9564571}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.883796457968402e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.976453}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.883796457968402e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060568.996458}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.883796457968402e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.0164442}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.883796457968402e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.036492}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060569.0567162, "x": -88.23520836643694, "y": 40.09285011755513, "z": 199.50478182422617, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060569.056469}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.883796457968402e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.056469}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.883796457968402e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.0764797}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.883796457968402e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.0964928}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.883796457968402e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.1164854}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.883796457968402e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.1364887}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060569.1566646, "x": -88.23520836643694, "y": 40.09285011755513, "z": 199.50478182422617, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060569.1564906}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.883796457968402e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.1564906}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.883796457968402e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.176446}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.883796457968402e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.1967325}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.883796457968402e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.2164893}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.883796457968402e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.236456}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060569.2569125, "x": -88.2352083807677, "y": 40.092850154153005, "z": 199.4888688125813, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060569.25651}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.883796457968402e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.25651}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.883796457968402e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.2764854}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.883796457968402e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.2964864}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.883796457968402e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.3164866}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091914e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.3364918}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060569.3566625, "x": -88.2352083807677, "y": 40.092850154153005, "z": 199.4888688125813, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060569.3564918}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091914e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.3564918}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091914e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.3764834}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091914e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.396454}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091914e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.4164603}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091914e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.4364552}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060569.4566631, "x": -88.2352083807677, "y": 40.092850154153005, "z": 199.4888688125813, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060569.4564695}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091914e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.4564695}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091914e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.4765265}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091914e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.496516}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091914e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.5164533}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091914e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.5364583}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060569.5565858, "x": -88.2352083807677, "y": 40.092850154153005, "z": 199.4888688125813, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060569.5564585}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091914e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.5564585}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091914e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.5764534}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091914e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.596514}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091914e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.6164865}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091914e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.6364555}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060569.656677, "x": -88.2352083807677, "y": 40.092850154153005, "z": 199.4888688125813, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060569.6565118}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091914e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.6565118}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091914e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.6764505}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091914e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.6964514}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091914e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.7164466}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091914e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.73646}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060569.7566135, "x": -88.23520841683988, "y": 40.09285023130767, "z": 199.47867499242068, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060569.7564864}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091914e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.7564864}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091914e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.776478}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091914e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.7964833}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091001e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.816457}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091001e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.8364825}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060569.856675, "x": -88.23520841683988, "y": 40.09285023130767, "z": 199.47867499242068, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060569.8565192}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091001e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.8565192}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091001e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.8764482}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091001e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.8964872}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091001e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.9165545}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091001e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.9364612}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060569.9566317, "x": -88.23520841683988, "y": 40.09285023130767, "z": 199.47867499242068, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060569.9564664}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091001e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.9564664}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091001e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.976457}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091001e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060569.9964583}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091001e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.0164626}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091001e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.0364816}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060570.056679, "x": -88.23520841683988, "y": 40.09285023130767, "z": 199.47867499242068, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060570.0564797}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091001e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.0564797}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091001e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.0764823}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091001e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.096462}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091001e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.1164787}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091001e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.136473}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060570.1567333, "x": -88.23520841683988, "y": 40.09285023130767, "z": 199.47867499242068, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060570.1565478}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091001e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.1565478}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091001e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.176449}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091001e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.196497}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091001e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.2164865}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091001e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.2364993}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060570.2566452, "x": -88.23520843495304, "y": 40.09285029191804, "z": 199.46695652897483, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060570.2564688}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.671505564091001e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.2564688}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.34971652491074e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.2764797}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.34971652491074e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.2964547}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.34971652491074e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.3164515}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.34971652491074e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.336479}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060570.3566687, "x": -88.23520843495304, "y": 40.09285029191804, "z": 199.46695652897483, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060570.3564727}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.34971652491074e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.3564727}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.34971652491074e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.3764753}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.34971652491074e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.3965135}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.34971652491074e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.4164798}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.34971652491074e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.4364536}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060570.4569123, "x": -88.23520843495304, "y": 40.09285029191804, "z": 199.46695652897483, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060570.456486}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.34971652491074e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.456486}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.34971652491074e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.4764495}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.34971652491074e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.4964597}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.34971652491074e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.5164495}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.34971652491074e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.5364566}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060570.556576, "x": -88.23520843495304, "y": 40.09285029191804, "z": 199.46695652897483, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060570.556456}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.34971652491074e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.556456}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.34971652491074e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.5764453}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.34971652491074e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.5964592}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.34971652491074e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.6164489}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.34971652491074e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.6364548}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060570.6565936, "x": -88.23520843495304, "y": 40.09285029191804, "z": 199.46695652897483, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060570.6564548}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.34971652491074e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.6564548}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.34971652491074e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.6764596}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.34971652491074e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.6964872}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.34971652491074e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.7165554}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.34971652491074e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.7364905}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060570.7566397, "x": -88.2352084402188, "y": 40.09285029293432, "z": 199.46274203491032, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060570.7564971}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.34971652491074e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.7564971}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.34971652491074e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.7764456}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.34971652491074e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.7964592}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.24692377633759e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.816456}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.24692377633759e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.836454}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060570.856665, "x": -88.2352084402188, "y": 40.09285029293432, "z": 199.46274203491032, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060570.8564694}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.24692377633759e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.8564694}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.24692377633759e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.8768435}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.24692377633759e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.896481}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.24692377633759e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.916447}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.24692377633759e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.9364548}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060570.956644, "x": -88.2352084402188, "y": 40.09285029293432, "z": 199.46274203491032, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060570.9564908}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.24692377633759e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.9564908}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.24692377633759e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.976483}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.24692377633759e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060570.996456}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.24692377633759e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.016447}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.24692377633759e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.0365136}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060571.0566564, "x": -88.2352084402188, "y": 40.09285029293432, "z": 199.46274203491032, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060571.056491}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.24692377633759e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.056491}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.24692377633759e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.0764494}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.24692377633759e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.09648}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.24692377633759e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.1164615}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.24692377633759e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.1364567}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060571.156602, "x": -88.2352084402188, "y": 40.09285029293432, "z": 199.46274203491032, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060571.1564567}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.24692377633759e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.1564567}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.24692377633759e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.1764843}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.24692377633759e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.1965046}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.24692377633759e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.2164793}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.24692377633759e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.236455}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060571.2565765, "x": -88.23520841235951, "y": 40.0928503335276, "z": 199.46040855082543, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060571.2564547}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.24692377633759e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.2564547}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9062560368191202e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.2764711}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9062560368191202e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.2964966}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9062560368191202e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.3164475}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9062560368191202e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.3364916}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060571.356611, "x": -88.23520841235951, "y": 40.0928503335276, "z": 199.46040855082543, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060571.356488}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9062560368191202e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.356488}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9062560368191202e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.3765001}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9062560368191202e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.3964863}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9062560368191202e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.4164746}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9062560368191202e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.4364834}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060571.4566116, "x": -88.23520841235951, "y": 40.0928503335276, "z": 199.46040855082543, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060571.456493}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9062560368191202e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.456493}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9062560368191202e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.4764864}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9062560368191202e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.496457}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9062560368191202e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.516469}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9062560368191202e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.5364537}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060571.5566242, "x": -88.23520841235951, "y": 40.0928503335276, "z": 199.46040855082543, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060571.556495}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9062560368191202e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.556495}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9062560368191202e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.576483}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9062560368191202e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.5964615}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9062560368191202e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.6165287}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9062560368191202e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.636482}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060571.656971, "x": -88.23520841235951, "y": 40.0928503335276, "z": 199.46040855082543, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060571.656547}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9062560368191202e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.656547}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9062560368191202e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.6764944}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9062560368191202e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.696458}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9062560368191202e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.7164493}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9062560368191202e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.7364469}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060571.7566934, "x": -88.23520848154908, "y": 40.092850443368675, "z": 199.4605361714122, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060571.7564785}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9062560368191202e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.7564785}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9062560368191202e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.7764845}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9062560368191202e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.7964556}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4651389373895535e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.8164754}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4651389373895535e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.8364794}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060571.8566818, "x": -88.23520848154908, "y": 40.092850443368675, "z": 199.4605361714122, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060571.8564935}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4651389373895535e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.8564935}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4651389373895535e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.8764923}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4651389373895535e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.8964856}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4651389373895535e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.9164562}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4651389373895535e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.9364548}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060571.9566538, "x": -88.23520848154908, "y": 40.092850443368675, "z": 199.4605361714122, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060571.9565048}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4651389373895535e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.9565048}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4651389373895535e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.976498}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4651389373895535e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060571.9964702}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4651389373895535e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.0164886}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4651389373895535e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.0364528}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060572.0565805, "x": -88.23520848154908, "y": 40.092850443368675, "z": 199.4605361714122, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060572.0564568}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4651389373895535e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.0564568}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4651389373895535e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.0764508}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4651389373895535e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.0964656}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4651389373895535e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.116475}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4651389373895535e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.1364534}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060572.1566088, "x": -88.23520848154908, "y": 40.092850443368675, "z": 199.4605361714122, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060572.1564834}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4651389373895535e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.1564834}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4651389373895535e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.1764514}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4651389373895535e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.196493}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4651389373895535e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.2164435}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4651389373895535e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.2365015}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060572.2566903, "x": -88.23520854356434, "y": 40.09285058543736, "z": 199.4638280700211, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060572.25647}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6069265764912957e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.25647}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6069265764912957e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.276519}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6069265764912957e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.296457}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6069265764912957e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.316486}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6069265764912957e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.336487}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060572.3566945, "x": -88.23520854356434, "y": 40.09285058543736, "z": 199.4638280700211, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060572.356503}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6069265764912957e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.356503}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6069265764912957e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.3764474}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6069265764912957e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.3964915}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6069265764912957e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.4165158}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6069265764912957e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.4364548}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060572.4566922, "x": -88.23520854356434, "y": 40.09285058543736, "z": 199.4638280700211, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060572.456476}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6069265764912957e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.456476}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6069265764912957e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.4764867}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6069265764912957e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.4964962}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6069265764912957e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.516479}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6069265764912957e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.536498}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060572.556699, "x": -88.23520854356434, "y": 40.09285058543736, "z": 199.4638280700211, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060572.5564756}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6069265764912957e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.5564756}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6069265764912957e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.5764844}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6069265764912957e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.5965104}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6069265764912957e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.6164892}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6069265764912957e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.6364536}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060572.6567905, "x": -88.23520854356434, "y": 40.09285058543736, "z": 199.4638280700211, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060572.6565316}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6069265764912957e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.6565316}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6069265764912957e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.6764529}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6069265764912957e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.6964898}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6069265764912957e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.7164881}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6069265764912957e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.736486}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060572.7566035, "x": -88.23520862130957, "y": 40.092850657039236, "z": 199.46907053872337, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060572.7564583}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6069265764912957e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.7564583}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6069265764912957e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.7764554}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6069265764912957e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.7964644}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6069265764912957e-22, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.8164566}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.041338279187511e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.8364608}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060572.856654, "x": -88.23520862130957, "y": 40.092850657039236, "z": 199.46907053872337, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060572.8565}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.041338279187511e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.8565}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.041338279187511e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.8764577}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.041338279187511e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.896524}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.041338279187511e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.9164593}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.041338279187511e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.9365013}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060572.956608, "x": -88.23520862130957, "y": 40.092850657039236, "z": 199.46907053872337, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060572.9564586}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.041338279187511e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.9564586}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.041338279187511e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.9764807}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.041338279187511e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060572.9965034}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.041338279187511e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.0164528}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.041338279187511e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.0365183}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060573.056624, "x": -88.23520862130957, "y": 40.092850657039236, "z": 199.46907053872337, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060573.0564823}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.041338279187511e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.0564823}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.041338279187511e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.0764534}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.041338279187511e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.0964491}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.041338279187511e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.116494}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.041338279187511e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.1364913}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060573.1566536, "x": -88.23520862130957, "y": 40.092850657039236, "z": 199.46907053872337, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060573.1565115}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.041338279187511e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.1565115}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.041338279187511e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.1764894}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.041338279187511e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.196505}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.041338279187511e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.2164516}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.041338279187511e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.2364826}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060573.2566786, "x": -88.23520869727284, "y": 40.09285071405354, "z": 199.46847829872428, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060573.256468}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.26231384900874e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.256468}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.26231384900874e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.2764556}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.26231384900874e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.2964804}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.26231384900874e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.3164492}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.26231384900874e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.3365052}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060573.3569107, "x": -88.23520869727284, "y": 40.09285071405354, "z": 199.46847829872428, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060573.3565516}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.26231384900874e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.3565516}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.26231384900874e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.3764856}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.26231384900874e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.3964858}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.26231384900874e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.4164808}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.26231384900874e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.4365156}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060573.4567595, "x": -88.23520869727284, "y": 40.09285071405354, "z": 199.46847829872428, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060573.4565248}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.26231384900874e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.4565248}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.26231384900874e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.4764512}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.26231384900874e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.496524}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.26231384900874e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.5164733}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.26231384900874e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.536503}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060573.5566635, "x": -88.23520869727284, "y": 40.09285071405354, "z": 199.46847829872428, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060573.5565045}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.26231384900874e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.5565045}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.26231384900874e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.5764725}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.26231384900874e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.5965383}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.26231384900874e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.6164484}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.26231384900874e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.6364849}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060573.6566348, "x": -88.23520869727284, "y": 40.09285071405354, "z": 199.46847829872428, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060573.656504}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.26231384900874e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.656504}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.26231384900874e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.6764925}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.26231384900874e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.6964827}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.26231384900874e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.7165916}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.26231384900874e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.7364826}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060573.7565844, "x": -88.23520871966522, "y": 40.09285077657599, "z": 199.47659910998556, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060573.7564807}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.26231384900874e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.7564807}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.444012716711021e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.776503}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.444012716711021e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.7964723}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.444012716711021e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.816441}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.444012716711021e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.8364763}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060573.856637, "x": -88.23520871966522, "y": 40.09285077657599, "z": 199.47659910998556, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060573.856491}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.444012716711021e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.856491}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.444012716711021e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.8765135}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.444012716711021e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.8964758}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.444012716711021e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.916492}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.444012716711021e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.936501}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060573.9566214, "x": -88.23520871966522, "y": 40.09285077657599, "z": 199.47659910998556, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060573.9564824}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.444012716711021e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.9564824}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.444012716711021e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.9764602}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.444012716711021e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060573.9964762}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.444012716711021e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060574.0164845}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.444012716711021e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060574.0364575}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060574.0565636, "x": -88.23520871966522, "y": 40.09285077657599, "z": 199.47659910998556, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060574.056447}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.444012716711021e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060574.056447}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.444012716711021e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060574.0764887}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.444012716711021e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060574.0964835}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.444012716711021e-23, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060574.116482}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.444012716711021e-23, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.07, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.1364775}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060574.1568441, "x": -88.23520871966522, "y": 40.09285077657599, "z": 199.47659910998556, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5603178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060574.156518}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.444012716711021e-23, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.1, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.156518}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.444012716711021e-23, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.1, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.1765072}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.444012716711021e-23, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.08, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.196491}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.444012716711021e-23, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.08, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.2164788}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.444012716711021e-23, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.04, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.2364545}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060574.2567532, "x": -88.23520877063514, "y": 40.092850852082435, "z": 199.48995812402543, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5567268162215617, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060574.256491}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.444012716711021e-23, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.03, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.256491}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.444012716711021e-23, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.03, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.2765293}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.444012716711021e-23, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.03, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.2964978}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.26052835240058e-23, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.03, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.3164582}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.26052835240058e-23, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.12, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.3364508}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060574.3566058, "x": -88.23520877063514, "y": 40.092850852082435, "z": 199.48995812402543, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5629428162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060574.3564737}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.26052835240058e-23, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.15, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.3564737}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.26052835240058e-23, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.15, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.3764827}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.26052835240058e-23, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.13, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.3964598}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.26052835240058e-23, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.13, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.4164557}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.26052835240058e-23, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.13, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.436593}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060574.4566967, "x": -88.23520877063514, "y": 40.092850852082435, "z": 199.48995812402543, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5677938162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060574.4564734}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.26052835240058e-23, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.24, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.4564734}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.26052835240058e-23, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.24, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.4764698}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.26052835240058e-23, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.36, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.4964566}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.26052835240058e-23, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.36, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.5164485}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.26052835240058e-23, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.5364628}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060574.5566123, "x": -88.23520877063514, "y": 40.092850852082435, "z": 199.48995812402543, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5791538162215617, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060574.5564795}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.26052835240058e-23, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.44, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.5564795}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.26052835240058e-23, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.44, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.5764828}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.26052835240058e-23, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.48, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.5964656}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.26052835240058e-23, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.48, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.6164827}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.26052835240058e-23, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.45, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.6364903}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060574.6566012, "x": -88.23520877063514, "y": 40.092850852082435, "z": 199.48995812402543, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5762388162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060574.6564555}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.26052835240058e-23, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.39, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.6564555}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.26052835240058e-23, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.39, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.676484}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.26052835240058e-23, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.48, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.6964679}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.26052835240058e-23, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.48, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.7164917}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.26052835240058e-23, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.58, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.7364523}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060574.7565603, "x": -88.2352097306008, "y": 40.09285093823494, "z": 199.5045695519061, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5964018162215616, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060574.756444}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.26052835240058e-23, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.72, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.756444}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.402204334191134e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.72, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.7765346}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.402204334191134e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.85, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.7964559}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.402204334191134e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.85, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.8164723}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.402204334191134e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.84, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.8364515}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060574.8566577, "x": -88.2352097306008, "y": 40.09285093823494, "z": 199.5045695519061, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5976938162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060574.8564532}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.402204334191134e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.74, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.8564532}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.402204334191134e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.74, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.8764482}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.402204334191134e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.79, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.8964765}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.402204334191134e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.79, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.9164484}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.402204334191134e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.936442}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060574.956849, "x": -88.2352097306008, "y": 40.09285093823494, "z": 199.5045695519061, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6274068162215616, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060574.9564652}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.402204334191134e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.17, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.9564652}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.402204334191134e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.17, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.9764676}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.402204334191134e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.26, "gear": 0, "accelerator_pedal_position": 0.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": 1744060574.996475}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.402204334191134e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.26, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.0164666}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.402204334191134e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.24, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.0364664}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060575.0567796, "x": -88.2352097306008, "y": 40.09285093823494, "z": 199.5045695519061, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.631846816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060575.056501}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.402204334191134e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.23, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.056501}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.402204334191134e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.23, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.0764508}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.402204334191134e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.42, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.0969186}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.402204334191134e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.42, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.1164546}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.402204334191134e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.57, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.136466}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060575.1565742, "x": -88.2352097306008, "y": 40.09285093823494, "z": 199.5045695519061, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6666068162215617, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060575.1564703}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.402204334191134e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.67, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.1564703}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.402204334191134e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.67, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.176477}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.402204334191134e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.1964438}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.402204334191134e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.216455}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.402204334191134e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.2365649}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060575.2566047, "x": -88.23521545302216, "y": 40.092850442942414, "z": 201.1335732964018, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6750468162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060575.2564611}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.402204334191134e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.77, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.2564611}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.402204334191134e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.77, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.2764452}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.402204334191134e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.01, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.2965662}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.402204334191134e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.01, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.3164482}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.7371202200050458e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.04, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.3364592}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060575.3565567, "x": -88.23521545302216, "y": 40.092850442942414, "z": 201.1335732964018, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7015668162215616, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060575.3564446}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.7371202200050458e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.07, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.3564446}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.7371202200050458e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.07, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.376493}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.7371202200050458e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.09, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.3964665}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.7371202200050458e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.09, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.416455}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.7371202200050458e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.15, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.4364746}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060575.4566832, "x": -88.23521545302216, "y": 40.092850442942414, "z": 201.1335732964018, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.728913816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060575.4564645}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.7371202200050458e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.36, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.4564645}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.7371202200050458e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.36, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.4764533}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.7371202200050458e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.46, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.4964476}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.7371202200050458e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.46, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.5164523}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.7371202200050458e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.42, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.53645}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060575.5566623, "x": -88.23521545302216, "y": 40.092850442942414, "z": 201.1335732964018, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7447218162215616, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060575.5564613}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.7371202200050458e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.52, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.5564613}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.7371202200050458e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.52, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.576442}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.7371202200050458e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.64, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.5964966}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.7371202200050458e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.64, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.6164753}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.7371202200050458e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.72, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.636482}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060575.6566033, "x": -88.23521545302216, "y": 40.092850442942414, "z": 201.1335732964018, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7746788162215617, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060575.6564503}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.7371202200050458e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.81, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.6564503}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.7371202200050458e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.81, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.6764472}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.7371202200050458e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.87, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.6964462}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.7371202200050458e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.87, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.7164497}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.7371202200050458e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.93, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.736493}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060575.7566037, "x": -88.2352284810052, "y": 40.09284958254985, "z": 201.14473857104264, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8007428162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060575.7564473}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.7371202200050458e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.05, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.7564473}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.1132259169389364e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.05, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.7764938}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.1132259169389364e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.19, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.796482}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.1132259169389364e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.19, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.8165004}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.1132259169389364e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.18, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.8364558}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060575.8565826, "x": -88.2352284810052, "y": 40.09284958254985, "z": 201.14473857104264, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8153418162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060575.8564491}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.1132259169389364e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.18, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.8564491}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.1132259169389364e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.28, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.8764782}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.1132259169389364e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.36, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.896445}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.1132259169389364e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.36, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.916485}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.1132259169389364e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.48, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.9364517}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060575.9565692, "x": -88.2352284810052, "y": 40.09284958254985, "z": 201.14473857104264, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8623818162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060575.9564676}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.1132259169389364e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.58, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.9564676}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.1132259169389364e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.58, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.976479}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.1132259169389364e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.65, "gear": 0, "accelerator_pedal_position": 0.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": 1744060575.996471}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.1132259169389364e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.65, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.0164795}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.1132259169389364e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.68, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.0364492}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060576.0565765, "x": -88.2352284810052, "y": 40.09284958254985, "z": 201.14473857104264, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.874641816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060576.056465}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.1132259169389364e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.68, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.056465}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.1132259169389364e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.79, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.0764434}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.1132259169389364e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.88, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.096452}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.1132259169389364e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.88, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.1164691}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.1132259169389364e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.94, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.1365006}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060576.1567059, "x": -88.2352284810052, "y": 40.09284958254985, "z": 201.14473857104264, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9074538162215617, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060576.1564708}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.1132259169389364e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.94, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.1564708}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.1132259169389364e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.01, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.1764536}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.1132259169389364e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.14, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.1966827}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.1132259169389364e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.14, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.216509}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.1132259169389364e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.13, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.236489}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060576.2569895, "x": -88.23524860581591, "y": 40.092848098018074, "z": 201.15624920817217, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.932286816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060576.2564905}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.1132259169389364e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.13, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.2564905}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.1132259169389364e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.26, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.276444}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.1132259169389364e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.35, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.2964897}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.034693293554217e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.35, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.3165092}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.034693293554217e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.42, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.3364477}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060576.3566642, "x": -88.23524860581591, "y": 40.092848098018074, "z": 201.15624920817217, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9715818162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060576.3564603}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.034693293554217e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.42, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.3564603}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.034693293554217e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.53, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.376441}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.034693293554217e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.61, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.3964453}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.034693293554217e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.61, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.4164488}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.034693293554217e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.55, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.4364421}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060576.4566717, "x": -88.23524860581591, "y": 40.092848098018074, "z": 201.15624920817217, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9897428162215616, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060576.4564843}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.034693293554217e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.55, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.4564843}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.034693293554217e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.75, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.476456}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.034693293554217e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.78, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.4964664}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.034693293554217e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.78, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.516448}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.034693293554217e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.81, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.536469}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060576.556685, "x": -88.23524860581591, "y": 40.092848098018074, "z": 201.15624920817217, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.027078816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060576.5564957}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.034693293554217e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.81, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.5564957}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.034693293554217e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.5764813}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.034693293554217e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.596455}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.034693293554217e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.6164882}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.034693293554217e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.6364925}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060576.6568024, "x": -88.23524860581591, "y": 40.092848098018074, "z": 201.15624920817217, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060576.6565123}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.034693293554217e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.6565123}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.034693293554217e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.6764505}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.034693293554217e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.6964443}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.034693293554217e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.716451}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.034693293554217e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.7364728}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060576.756658, "x": -88.23527544647528, "y": 40.09284611458593, "z": 201.14245184706692, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060576.7564766}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.034693293554217e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.7564766}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.034693293554217e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.776473}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.034693293554217e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.7965107}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.034693293554217e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.8164465}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.034693293554217e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.83645}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060576.85677, "x": -88.23527544647528, "y": 40.09284611458593, "z": 201.14245184706692, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060576.856554}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.732759628424263e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.856554}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.732759628424263e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.56, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.8764722}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.732759628424263e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.8964844}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.732759628424263e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.9164817}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.732759628424263e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.936482}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060576.9566033, "x": -88.23527544647528, "y": 40.09284611458593, "z": 201.14245184706692, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060576.956475}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.732759628424263e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.956475}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.732759628424263e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.9764798}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.732759628424263e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.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": 1744060576.996489}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.732759628424263e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.0164409}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.732759628424263e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.0365129}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060577.0566769, "x": -88.23527544647528, "y": 40.09284611458593, "z": 201.14245184706692, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.210126816221561, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060577.0564852}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.732759628424263e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.0564852}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.732759628424263e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.076445}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.732759628424263e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.0964646}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.732759628424263e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.1165388}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.732759628424263e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.1364431}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060577.156634, "x": -88.23527544647528, "y": 40.09284611458593, "z": 201.14245184706692, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.223742816221561, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060577.1564865}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.732759628424263e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.1564865}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.732759628424263e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.1764731}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.732759628424263e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.1964529}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.732759628424263e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.2164788}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.732759628424263e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.2364736}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060577.256675, "x": -88.2353083632597, "y": 40.09284354099884, "z": 201.14439288773553, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.2531018162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060577.256483}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.732759628424263e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.256483}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.59053335474551e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.2764714}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.59053335474551e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.2964754}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.59053335474551e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.3164804}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.59053335474551e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.3364549}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060577.3567538, "x": -88.2353083632597, "y": 40.09284354099884, "z": 201.14439288773553, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060577.3565054}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.59053335474551e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.3565054}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.59053335474551e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.3764813}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.59053335474551e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.396442}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.59053335474551e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.4164782}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.59053335474551e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.4364414}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060577.4566984, "x": -88.2353083632597, "y": 40.09284354099884, "z": 201.14439288773553, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060577.4564917}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.59053335474551e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.4564917}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.59053335474551e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.54, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.4764462}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.59053335474551e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.496482}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.59053335474551e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.516491}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.59053335474551e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.5365102}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060577.5566227, "x": -88.2353083632597, "y": 40.09284354099884, "z": 201.14439288773553, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.324461816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060577.5564477}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.59053335474551e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.5564477}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.59053335474551e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.576444}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.59053335474551e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.5964637}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.59053335474551e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.6164813}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.59053335474551e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.636446}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060577.656613, "x": -88.2353083632597, "y": 40.09284354099884, "z": 201.14439288773553, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.355758816221561, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060577.6564486}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.59053335474551e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.6564486}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.59053335474551e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.6764436}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.59053335474551e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.6965709}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.59053335474551e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.716479}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.59053335474551e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.7364788}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060577.7566085, "x": -88.23534613713996, "y": 40.092840272483286, "z": 201.13146425997863, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060577.7564812}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.59053335474551e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.7564812}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.59053335474551e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.7765148}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.59053335474551e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.7964847}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.59053335474551e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.8164542}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.59053335474551e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.8364704}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060577.8566415, "x": -88.23534613713996, "y": 40.092840272483286, "z": 201.13146425997863, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.400926816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060577.8564572}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5786305062320547e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.8564572}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5786305062320547e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.87647}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5786305062320547e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.896503}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5786305062320547e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.916448}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5786305062320547e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.9364414}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060577.9568355, "x": -88.23534613713996, "y": 40.092840272483286, "z": 201.13146425997863, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060577.9565144}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5786305062320547e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.9565144}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5786305062320547e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.976445}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5786305062320547e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.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": 1744060577.9965043}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5786305062320547e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.0165074}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5786305062320547e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.0364408}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060578.0566916, "x": -88.23534613713996, "y": 40.092840272483286, "z": 201.13146425997863, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060578.0564985}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5786305062320547e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.0564985}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5786305062320547e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.0764434}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5786305062320547e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.0964484}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5786305062320547e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.1164453}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5786305062320547e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.1364403}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060578.1566455, "x": -88.23534613713996, "y": 40.092840272483286, "z": 201.13146425997863, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060578.156495}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5786305062320547e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.156495}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5786305062320547e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.1764436}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5786305062320547e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.1965034}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5786305062320547e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.2164793}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5786305062320547e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.236485}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060578.2568798, "x": -88.235387110799, "y": 40.09283590536509, "z": 201.13837346458806, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.400926816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060578.256523}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5786305062320547e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.256523}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.660213123810967e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.276448}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.660213123810967e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.2964797}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.660213123810967e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.3164768}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.660213123810967e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.3364444}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060578.3565938, "x": -88.235387110799, "y": 40.09283590536509, "z": 201.13837346458806, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.340958816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060578.3564503}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.660213123810967e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.3564503}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.660213123810967e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.3764353}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.660213123810967e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.3964775}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.660213123810967e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.54, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.4164915}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.660213123810967e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.436479}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060578.4565713, "x": -88.235387110799, "y": 40.09283590536509, "z": 201.13837346458806, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060578.4564452}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.660213123810967e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.4564452}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.660213123810967e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.4764452}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.660213123810967e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.496495}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.660213123810967e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.5164678}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.660213123810967e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.536476}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060578.556605, "x": -88.235387110799, "y": 40.09283590536509, "z": 201.13837346458806, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060578.556477}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.660213123810967e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.556477}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.660213123810967e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.576435}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.660213123810967e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.5964806}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.660213123810967e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.6164396}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.660213123810967e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.63646}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060578.6566365, "x": -88.235387110799, "y": 40.09283590536509, "z": 201.13837346458806, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.267117816221561, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060578.6564837}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.660213123810967e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.6564837}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.660213123810967e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.6764684}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.660213123810967e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.6964447}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.660213123810967e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.7164783}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.660213123810967e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.7364872}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060578.7567966, "x": -88.23542769969158, "y": 40.0928316161765, "z": 201.13803552495455, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.340958816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060578.7565072}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.660213123810967e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.7565072}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.660213123810967e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.54, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.776477}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.660213123810967e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.54, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.7964957}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.660213123810967e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.8164752}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.73119941993947e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.8364742}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060578.8566427, "x": -88.23542769969158, "y": 40.0928316161765, "z": 201.13803552495455, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.2531018162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060578.85649}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.73119941993947e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.85649}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.73119941993947e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.8764465}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.73119941993947e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.8965127}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.73119941993947e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.9164534}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.73119941993947e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.9364412}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060578.956695, "x": -88.23542769969158, "y": 40.0928316161765, "z": 201.13803552495455, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060578.9564934}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.73119941993947e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.9564934}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.73119941993947e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.9764755}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.73119941993947e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.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": 1744060578.996465}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.73119941993947e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.0164678}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.73119941993947e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.036473}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060579.05667, "x": -88.23542769969158, "y": 40.0928316161765, "z": 201.13803552495455, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.223742816221561, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060579.0564811}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.73119941993947e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.0564811}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.73119941993947e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.0765312}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.73119941993947e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.0964463}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.73119941993947e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.1164777}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.73119941993947e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.136511}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060579.1566656, "x": -88.23542769969158, "y": 40.0928316161765, "z": 201.13803552495455, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.210126816221561, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060579.1564972}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.73119941993947e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.1564972}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.73119941993947e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.1765153}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.73119941993947e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.1964734}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.73119941993947e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.2164898}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.73119941993947e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.2364762}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060579.2566268, "x": -88.23546392422558, "y": 40.09282789393926, "z": 201.1348967113914, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.183278816221561, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060579.2564552}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.685767640147276e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.2564552}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.685767640147276e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.27648}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.685767640147276e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.2964668}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.685767640147276e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.3164682}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.685767640147276e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.3364713}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060579.3566053, "x": -88.23546392422558, "y": 40.09282789393926, "z": 201.1348967113914, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060579.356474}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.685767640147276e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.356474}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.685767640147276e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.376492}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.685767640147276e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.3964787}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.685767640147276e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.4164605}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.685767640147276e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.4364655}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060579.456573, "x": -88.23546392422558, "y": 40.09282789393926, "z": 201.1348967113914, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060579.4564452}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.685767640147276e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.4564452}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.685767640147276e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.4764674}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.685767640147276e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.4964466}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.685767640147276e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.5164492}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.685767640147276e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.5364594}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060579.5566115, "x": -88.23546392422558, "y": 40.09282789393926, "z": 201.1348967113914, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060579.5564778}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.685767640147276e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.5564778}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.685767640147276e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.5764656}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.685767640147276e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.5965555}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.685767640147276e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.6164854}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.685767640147276e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.6364398}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060579.656773, "x": -88.23546392422558, "y": 40.09282789393926, "z": 201.1348967113914, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060579.6564739}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.685767640147276e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.6564739}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.685767640147276e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.6764781}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.685767640147276e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.6965268}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.685767640147276e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.716474}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.685767640147276e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.7364655}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060579.75669, "x": -88.23549566200495, "y": 40.092824535293424, "z": 201.13401615086912, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060579.7564907}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.685767640147276e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.7564907}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.685767640147276e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.7764854}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.685767640147276e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.7964633}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.523263797212818e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.8164818}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.523263797212818e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.91, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.8364697}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060579.857283, "x": -88.23549566200495, "y": 40.092824535293424, "z": 201.13401615086912, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060579.856581}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.523263797212818e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.856581}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.523263797212818e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.8764427}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.523263797212818e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.8964438}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.523263797212818e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.916584}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.523263797212818e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.9365406}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060579.9566529, "x": -88.23549566200495, "y": 40.092824535293424, "z": 201.13401615086912, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060579.956484}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.523263797212818e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.956484}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.523263797212818e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.9764695}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.523263797212818e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.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": 1744060579.9965158}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.523263797212818e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.0164776}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.523263797212818e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.036697}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060580.0566728, "x": -88.23549566200495, "y": 40.092824535293424, "z": 201.13401615086912, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060580.0564811}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.523263797212818e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.0564811}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.523263797212818e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.0764737}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.523263797212818e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.0964844}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.523263797212818e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.116433}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.523263797212818e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.1364465}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060580.156632, "x": -88.23549566200495, "y": 40.092824535293424, "z": 201.13401615086912, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9483428162215617, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060580.1564703}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.523263797212818e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.25, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.1564703}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.523263797212818e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.25, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.1764696}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.523263797212818e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.25, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.1965773}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.523263797212818e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.17, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.2164671}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.523263797212818e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.17, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.236442}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060580.256718, "x": -88.23552264390162, "y": 40.092821758997275, "z": 201.16061721138726, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9269988162215617, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060580.256479}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.234320359165449e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.09, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.256479}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.234320359165449e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.07, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.276468}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.234320359165449e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.07, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.2964985}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.234320359165449e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.07, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.316447}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.234320359165449e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.07, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.3364954}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060580.3566184, "x": -88.23552264390162, "y": 40.092821758997275, "z": 201.16061721138726, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9087428162215616, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060580.3564532}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.234320359165449e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.95, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.3564532}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.234320359165449e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.85, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.3764682}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.234320359165449e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.85, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.396489}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.234320359165449e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.78, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.4164464}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.234320359165449e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.78, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.4364696}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060580.4566443, "x": -88.23552264390162, "y": 40.092821758997275, "z": 201.16061721138726, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.887101816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060580.4564636}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.234320359165449e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.78, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.4564636}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.234320359165449e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.73, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.476473}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.234320359165449e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.73, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.4964812}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.234320359165449e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.71, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.5164762}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.234320359165449e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.71, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.536466}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060580.5568328, "x": -88.23552264390162, "y": 40.092821758997275, "z": 201.16061721138726, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8672618162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060580.5565245}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.234320359165449e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.62, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.5565245}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.234320359165449e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.51, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.5765102}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.234320359165449e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.51, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.5965087}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.234320359165449e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.49, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.616498}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.234320359165449e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.49, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.6364872}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060580.656633, "x": -88.23552264390162, "y": 40.092821758997275, "z": 201.16061721138726, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8479338162215617, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060580.656478}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.234320359165449e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.46, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.656478}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.234320359165449e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.42, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.6764665}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.234320359165449e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.42, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.6964974}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.234320359165449e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.39, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.7164762}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.234320359165449e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.39, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.7365866}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060580.756619, "x": -88.23554508870403, "y": 40.09281932078564, "z": 201.17886038881508, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8291178162215616, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060580.7564692}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.234320359165449e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.3, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.7564692}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.234320359165449e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.19, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.7764814}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.234320359165449e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.19, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.796445}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.82734366153387e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.18, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.8164778}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.82734366153387e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.18, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.8365524}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060580.856665, "x": -88.23554508870403, "y": 40.09281932078564, "z": 201.17886038881508, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8142068162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060580.8564837}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.82734366153387e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.17, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.8564837}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.82734366153387e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.05, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.8764656}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.82734366153387e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.05, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.896481}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.82734366153387e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.0, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.916435}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.82734366153387e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.0, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.9364748}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060580.956582, "x": -88.23554508870403, "y": 40.09281932078564, "z": 201.17886038881508, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.789742816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060580.9564471}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.82734366153387e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.95, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.9564471}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.82734366153387e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.92, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.9764805}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.82734366153387e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.92, "gear": 0, "accelerator_pedal_position": 0.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": 1744060580.9965012}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.82734366153387e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.87, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.0164516}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.82734366153387e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.87, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.0364666}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060581.0566285, "x": -88.23554508870403, "y": 40.09281932078564, "z": 201.17886038881508, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7746788162215617, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060581.0564473}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.82734366153387e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.81, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.0564473}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.82734366153387e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.75, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.0764656}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.82734366153387e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.75, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.0964646}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.82734366153387e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.74, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.1164947}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.82734366153387e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.74, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.1364663}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060581.1566672, "x": -88.23554508870403, "y": 40.09281932078564, "z": 201.17886038881508, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7610418162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060581.1564813}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.82734366153387e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.68, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.1564813}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.82734366153387e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.67, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.1764646}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.82734366153387e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.67, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.196448}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.82734366153387e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.58, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.2164679}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.82734366153387e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.58, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.2364626}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060581.2569463, "x": -88.23556271245454, "y": 40.09281736555375, "z": 201.21569947176292, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7437188162215618, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060581.256509}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.293473080522802e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.51, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.256509}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.293473080522802e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.43, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.2764437}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.293473080522802e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.43, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.2964463}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.293473080522802e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.3164475}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.293473080522802e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.3364363}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060581.3570561, "x": -88.23556271245454, "y": 40.09281736555375, "z": 201.21569947176292, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7279428162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060581.3565052}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.293473080522802e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.35, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.3565052}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.293473080522802e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.33, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.3764772}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.293473080522802e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.33, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.3964462}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.293473080522802e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.26, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.416471}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.293473080522802e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.26, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.4364939}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060581.4567323, "x": -88.23556271245454, "y": 40.09281736555375, "z": 201.21569947176292, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7117418162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060581.45649}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.293473080522802e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.18, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.45649}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.293473080522802e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.12, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.4764695}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.293473080522802e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.12, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.4965625}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.293473080522802e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.516483}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.293473080522802e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.5364828}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060581.5566528, "x": -88.23556271245454, "y": 40.09281736555375, "z": 201.21569947176292, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7024818162215616, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060581.5564785}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.293473080522802e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.08, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.5564785}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.293473080522802e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.576471}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.293473080522802e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.5964477}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.293473080522802e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.98, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.6164794}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.293473080522802e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.98, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.6364784}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060581.6566215, "x": -88.23556271245454, "y": 40.09281736555375, "z": 201.21569947176292, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6836868162215617, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060581.6564486}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.293473080522802e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.87, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.6564486}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.293473080522802e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.84, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.6764693}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.293473080522802e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.84, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.6964655}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.293473080522802e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.77, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.7164562}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.293473080522802e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.77, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.7364798}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060581.7566574, "x": -88.2355756859468, "y": 40.09281592880842, "z": 201.2294318286146, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.673342816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060581.756462}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.293473080522802e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.75, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.756462}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.293473080522802e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.67, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.776448}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.636577486968545e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.67, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.7964811}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.636577486968545e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.62, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.816464}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.636577486968545e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.62, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.836446}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060581.85663, "x": -88.2355756859468, "y": 40.09281592880842, "z": 201.2294318286146, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6591818162215617, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060581.856478}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.636577486968545e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.58, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.856478}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.636577486968545e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.56, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.8764367}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.636577486968545e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.56, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.8964703}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.636577486968545e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.48, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.9164727}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.636577486968545e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.48, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.9364765}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060581.9567652, "x": -88.2355756859468, "y": 40.09281592880842, "z": 201.2294318286146, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6495338162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060581.9565108}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.636577486968545e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.46, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.9565108}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.636577486968545e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.38, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.9764676}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.636577486968545e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.38, "gear": 0, "accelerator_pedal_position": 0.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": 1744060581.9964545}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.636577486968545e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.34, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.0164676}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.636577486968545e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.34, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.0364738}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060582.0566373, "x": -88.2355756859468, "y": 40.09281592880842, "z": 201.2294318286146, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6378788162215616, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060582.0564606}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.636577486968545e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.31, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.0564606}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.636577486968545e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.27, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.0764797}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.636577486968545e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.27, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.096457}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.636577486968545e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.1164763}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.636577486968545e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.1364706}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060582.1567717, "x": -88.2355756859468, "y": 40.09281592880842, "z": 201.2294318286146, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6266738162215617, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060582.1564705}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.636577486968545e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.16, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.1564705}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.636577486968545e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.1764698}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.636577486968545e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.1964977}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.636577486968545e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.06, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.2164805}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.636577486968545e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.06, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.236448}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060582.256649, "x": -88.23558403405626, "y": 40.09281421232241, "z": 201.26702365480384, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6173268162215617, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060582.2564857}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.636577486968545e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.03, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.2564857}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.636577486968545e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.03, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.2764428}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.636577486968545e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.98, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.2964897}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.636577486968545e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.94, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.3164423}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.636577486968545e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.94, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.3364766}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060582.356676, "x": -88.23558403405626, "y": 40.09281421232241, "z": 201.26702365480384, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6083178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060582.3564892}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.866787049181744e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.3564892}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.866787049181744e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.376469}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.866787049181744e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.85, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.3964493}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.866787049181744e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.81, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.4164355}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.866787049181744e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.81, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.4364412}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060582.4568305, "x": -88.23558403405626, "y": 40.09281421232241, "z": 201.26702365480384, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5996468162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060582.4565036}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.866787049181744e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.77, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.4565036}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.866787049181744e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.77, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.4764364}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.866787049181744e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.72, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.4964714}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.866787049181744e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.67, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.5164666}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.866787049181744e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.67, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.5364487}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060582.5570483, "x": -88.23558403405626, "y": 40.09281421232241, "z": 201.26702365480384, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5919428162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060582.5566366}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.866787049181744e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.65, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.5566366}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.866787049181744e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.65, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.5764935}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.866787049181744e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.5964987}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.866787049181744e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.55, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.6164656}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.866787049181744e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.55, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.6365147}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060582.6565928, "x": -88.23558403405626, "y": 40.09281421232241, "z": 201.26702365480384, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5845268162215618, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060582.656469}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.866787049181744e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.53, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.656469}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.866787049181744e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.53, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.676464}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.866787049181744e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.49, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.6964676}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.866787049181744e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.44, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.7165246}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.866787049181744e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.44, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.7364755}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060582.756616, "x": -88.23558848603653, "y": 40.092814032160256, "z": 201.30306546884918, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5779818162215618, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060582.7564776}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.866787049181744e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.42, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.7564776}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.980801075077272e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.42, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.7764375}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.980801075077272e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.37, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.796482}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.980801075077272e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.33, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.8164394}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.980801075077272e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.33, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.836465}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060582.856728, "x": -88.23558848603653, "y": 40.092814032160256, "z": 201.30306546884918, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.571678816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060582.856492}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.980801075077272e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.31, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.856492}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.980801075077272e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.31, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.8764896}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.980801075077272e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.26, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.8965068}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.980801075077272e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.22, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.9164383}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.980801075077272e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.22, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.936432}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060582.9566958, "x": -88.23558848603653, "y": 40.092814032160256, "z": 201.30306546884918, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5656178162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060582.956487}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.980801075077272e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.956487}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.980801075077272e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.9764419}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.980801075077272e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.17, "gear": 0, "accelerator_pedal_position": 0.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": 1744060582.9964862}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.980801075077272e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.13, "gear": 0, "accelerator_pedal_position": 0.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": 1744060583.0164359}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.980801075077272e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.13, "gear": 0, "accelerator_pedal_position": 0.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": 1744060583.0365283}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060583.0568318, "x": -88.23558848603653, "y": 40.092814032160256, "z": 201.30306546884918, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5608388162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060583.056517}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.980801075077272e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.11, "gear": 0, "accelerator_pedal_position": 0.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": 1744060583.056517}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.980801075077272e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.11, "gear": 0, "accelerator_pedal_position": 0.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": 1744060583.0764704}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.980801075077272e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.08, "gear": 0, "accelerator_pedal_position": 0.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": 1744060583.0964704}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.980801075077272e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.04, "gear": 0, "accelerator_pedal_position": 0.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": 1744060583.116494}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.980801075077272e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.04, "gear": 0, "accelerator_pedal_position": 0.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": 1744060583.1364422}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060583.1566744, "x": -88.23558848603653, "y": 40.092814032160256, "z": 201.30306546884918, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5572338162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060583.1564732}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.980801075077272e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.04, "gear": 0, "accelerator_pedal_position": 0.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": 1744060583.1564732}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.980801075077272e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.04, "gear": 0, "accelerator_pedal_position": 0.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": 1744060583.1764388}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.980801075077272e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.02, "gear": 0, "accelerator_pedal_position": 0.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": 1744060583.1964886}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.980801075077272e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01, "gear": 0, "accelerator_pedal_position": 0.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": 1744060583.2165}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.980801075077272e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01, "gear": 0, "accelerator_pedal_position": 0.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": 1744060583.2364743}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060583.2566335, "x": -88.23558983715576, "y": 40.09281314419649, "z": 201.30838686460848, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5557188162215616, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060583.2564797}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.980801075077272e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01, "gear": 0, "accelerator_pedal_position": 0.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": 1744060583.2564797}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.980801075077272e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01, "gear": 0, "accelerator_pedal_position": 0.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": 1744060583.2764733}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.980801075077272e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.2965357}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.980801075077272e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.3164666}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0025325460885647e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.3364413}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060583.3565624, "x": -88.23558983715576, "y": 40.09281314419649, "z": 201.30838686460848, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060583.356441}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0025325460885647e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.356441}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0025325460885647e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.3764656}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0025325460885647e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.3964531}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0025325460885647e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.4164338}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0025325460885647e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.4364774}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060583.456877, "x": -88.23558983715576, "y": 40.09281314419649, "z": 201.30838686460848, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060583.4565208}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0025325460885647e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.4565208}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0025325460885647e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.476466}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0025325460885647e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.4964454}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0025325460885647e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.5165112}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0025325460885647e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.5364997}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060583.556928, "x": -88.23558983715576, "y": 40.09281314419649, "z": 201.30838686460848, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060583.5564606}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0025325460885647e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.5564606}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0025325460885647e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.5764406}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0025325460885647e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.596506}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0025325460885647e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.6164856}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0025325460885647e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.6365032}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060583.656567, "x": -88.23558983715576, "y": 40.09281314419649, "z": 201.30838686460848, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060583.6564422}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0025325460885647e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.6564422}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0025325460885647e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.6764731}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0025325460885647e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.6964486}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0025325460885647e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.7164724}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0025325460885647e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.7364383}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060583.756842, "x": -88.23559001137703, "y": 40.09281209026382, "z": 201.2924423587878, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060583.756483}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0042253248758052e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.756483}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0042253248758052e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.7764666}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0042253248758052e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.7965403}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0042253248758052e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.816487}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0042253248758052e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.8364832}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060583.8568916, "x": -88.23559001137703, "y": 40.09281209026382, "z": 201.2924423587878, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060583.856528}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0042253248758052e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.856528}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0042253248758052e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.8764653}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0042253248758052e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.8964915}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0042253248758052e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.916481}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0042253248758052e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.9364886}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060583.9566624, "x": -88.23559001137703, "y": 40.09281209026382, "z": 201.2924423587878, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060583.9564471}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0042253248758052e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.9564471}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0042253248758052e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.9764569}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0042253248758052e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060583.996502}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0042253248758052e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.0165017}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0042253248758052e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.036477}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060584.0566907, "x": -88.23559001137703, "y": 40.09281209026382, "z": 201.2924423587878, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060584.0565112}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0042253248758052e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.0565112}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0042253248758052e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.076465}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0042253248758052e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.0964475}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0042253248758052e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.1164968}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0042253248758052e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.1365135}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060584.1566365, "x": -88.23559001137703, "y": 40.09281209026382, "z": 201.2924423587878, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060584.1564524}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0042253248758052e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.1564524}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0042253248758052e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.1764386}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0042253248758052e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.1964493}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0042253248758052e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.2164605}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0042253248758052e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.2365513}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060584.2565954, "x": -88.23559018715854, "y": 40.092811260095665, "z": 201.29093072098362, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060584.2564766}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0042253248758052e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.2564766}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0042253248758052e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.276459}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0056555706965822e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.296462}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0056555706965822e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.3164515}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0056555706965822e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.3364425}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060584.3566418, "x": -88.23559018715854, "y": 40.092811260095665, "z": 201.29093072098362, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060584.356446}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0056555706965822e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.356446}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0056555706965822e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.3764393}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0056555706965822e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.3964424}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0056555706965822e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.4164336}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0056555706965822e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.4364395}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060584.4566126, "x": -88.23559018715854, "y": 40.092811260095665, "z": 201.29093072098362, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060584.456443}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0056555706965822e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.456443}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0056555706965822e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.476436}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0056555706965822e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.496442}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0056555706965822e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.5164506}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0056555706965822e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.536476}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060584.5568364, "x": -88.23559018715854, "y": 40.092811260095665, "z": 201.29093072098362, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060584.5564744}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0056555706965822e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.5564744}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0056555706965822e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.5764737}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0056555706965822e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.5964742}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0056555706965822e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.616442}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0056555706965822e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.636437}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060584.6566534, "x": -88.23559018715854, "y": 40.092811260095665, "z": 201.29093072098362, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060584.6564753}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0056555706965822e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.6564753}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0056555706965822e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.6764352}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0056555706965822e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.6965005}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0056555706965822e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.716467}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0056555706965822e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.7364204}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060584.7565472, "x": -88.23559016944917, "y": 40.09281069003803, "z": 201.28400123893363, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060584.7564356}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0056555706965822e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.7564356}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0056555706965822e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.7764733}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0056555706965822e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.7964468}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0056555706965822e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.8164341}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0062898820519205e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.836495}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060584.8565521, "x": -88.23559016944917, "y": 40.09281069003803, "z": 201.28400123893363, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060584.8564377}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0062898820519205e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.8564377}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0062898820519205e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.8764706}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0062898820519205e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.8964813}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0062898820519205e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.9164855}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0062898820519205e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.936481}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060584.9565396, "x": -88.23559016944917, "y": 40.09281069003803, "z": 201.28400123893363, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060584.9564347}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0062898820519205e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.9564347}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0062898820519205e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.9764383}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0062898820519205e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060584.9964423}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0062898820519205e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060585.016512}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0062898820519205e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060585.0365279}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060585.0568163, "x": -88.23559016944917, "y": 40.09281069003803, "z": 201.28400123893363, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060585.05647}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0062898820519205e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060585.05647}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0062898820519205e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060585.076441}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0062898820519205e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060585.0964346}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0062898820519205e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060585.1164353}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0062898820519205e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060585.1364892}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060585.1566212, "x": -88.23559016944917, "y": 40.09281069003803, "z": 201.28400123893363, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060585.15645}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0062898820519205e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060585.15645}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0062898820519205e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060585.176433}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0062898820519205e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060585.1964703}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0062898820519205e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060585.2165127}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0062898820519205e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060585.2364526}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060585.25663, "x": -88.23558999641129, "y": 40.09281032292764, "z": 201.28768039699955, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060585.2564368}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0062898820519205e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060585.2564368}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0062922214487287e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060585.276445}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0062922214487287e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060585.2964609}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0062922214487287e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060585.3164833}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0062922214487287e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060585.3364446}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060585.3573177, "x": -88.23558999641129, "y": 40.09281032292764, "z": 201.28768039699955, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060585.3568673}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0062922214487287e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060585.3568673}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0062922214487287e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060585.3764718}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0062922214487287e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060585.3964396}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0062922214487287e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060585.4164422}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0062922214487287e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060585.4364357}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744060585.4567752, "x": -88.23558999641129, "y": 40.09281032292764, "z": 201.28768039699955, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744060585.456467}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0062922214487287e-18, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744060585.456467}
diff --git a/testing/racing_logs/launch_control/meta.yaml b/testing/racing_logs/launch_control/meta.yaml
new file mode 100644
index 000000000..0dc126406
--- /dev/null
+++ b/testing/racing_logs/launch_control/meta.yaml
@@ -0,0 +1,19 @@
+events:
+- description: Ctrl+C pressed, switching to recovery mode
+ time: 1744060585.4767659
+ vehicle_time: 1744060585.476444
+- description: Mission execution ended
+ time: 1744060585.481435
+ vehicle_time: 1744060585.476444
+exit_reason: normal exit
+git_branch: racing
+git_commit_id: 2e36aeb7a55246289008a8f0a7de7f84bdbec5e6
+pipelines:
+- name: drive
+ time: 1744060568.3554397
+ vehicle_time: 1744060568.2552168
+- name: recovery
+ time: 1744060585.4778304
+ vehicle_time: 1744060585.476444
+start_time: 1744060568.2330396
+start_time_human_readable: '2025-04-07 16:16:08'
diff --git a/testing/racing_logs/launch_control/settings.yaml b/testing/racing_logs/launch_control/settings.yaml
new file mode 100644
index 000000000..d41e50bb8
--- /dev/null
+++ b/testing/racing_logs/launch_control/settings.yaml
@@ -0,0 +1,325 @@
+control:
+ longitudinal_control:
+ pid_d: 0.0
+ pid_i: 0.03
+ pid_p: 0.8
+ pure_pursuit:
+ crosstrack_gain: 0.3
+ desired_speed: racing
+ launch_control: 0
+ lookahead: 2.0
+ lookahead_scale: 2.0
+ recovery:
+ brake_amount: 0.5
+ brake_speed: 2.0
+model_predictive_controller:
+ dt: 0.1
+ lookahead: 20
+planning:
+ longitudinal_plan:
+ acceleration: 0.5
+ deceleration: 2.0
+ desired_speed: 1.0
+ max_deceleration: 6.0
+ min_deceleration: 0.5
+ mode: real
+ planner: dt
+ yield_deceleration: 0.5
+ yielder: expert
+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:
+ - all
+ 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:
+ perception_normalization: StandardPerceptionNormalizer
+ state_estimation: GNSSStateEstimator
+ planning:
+ motion_planning:
+ args:
+ - null
+ type: RouteToTrajectoryPlanner
+ route_planning:
+ args:
+ - GEMstack/knowledge/routes/forward_15m.csv
+ type: StaticRoutePlanner
+ trajectory_tracking:
+ print: false
+ type: pure_pursuit.PurePursuitTrajectoryTracker
+ log:
+ components:
+ - state_estimation
+ - trajectory_tracking
+ ros_topics: []
+ vehicle_interface: true
+ mission_execution: StandardExecutor
+ mode: hardware
+ 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: gem_hardware.GEMHardwareInterface
+simulator:
+ dt: 0.01
+ gnss_emulator:
+ dt: 0.05
+ real_time_multiplier: 1.0
+vehicle:
+ calibration:
+ calibration_date: '2025-02-25'
+ front_camera:
+ center_position:
+ - 1.75864913
+ - 0.01238124
+ - 1.54408419
+ reference: rear_axle_center
+ rotation:
+ - - 0.00349517
+ - -0.03239524
+ - 0.99946903
+ - - -0.99996547
+ - 0.00742285
+ - 0.0037375
+ - - -0.00753999
+ - -0.99944757
+ - -0.03236817
+ gnss_location:
+ - 1.1
+ - 0
+ - 1.62
+ gnss_yaw: 0.0
+ rear_axle_height: 0.2794
+ reference: rear_axle_center
+ top_lidar:
+ position:
+ - 1.1
+ - 0.03773044170906172
+ - 1.9525244316515322
+ reference: rear_axle_center
+ rotation:
+ - - 0.99941328
+ - 0.02547416
+ - 0.02289458
+ - - -0.02530855
+ - 0.99965159
+ - -0.00749488
+ - - -0.02307753
+ - 0.00691106
+ - 0.99970979
+ control_defaults:
+ accelerator_pedal_speed: 3.0
+ brake_pedal_speed: 3.0
+ steering_wheel_speed: 4.0
+ dynamics:
+ acceleration_deadband: 0.1
+ acceleration_model: hang_v1
+ accelerator_active_range:
+ - 0.2
+ - 1.0
+ aerodynamic_drag_coefficient: 0.01
+ brake_active_range:
+ - 0.5
+ - 1
+ gravity: 9.81
+ internal_dry_deceleration: 0.2
+ internal_viscous_deceleration: 0.05
+ lateral_friction: 1.0
+ longitudinal_friction: 1.0
+ mass: 700.0
+ max_accelerator_acceleration:
+ - 0.0
+ - 5.0
+ max_accelerator_acceleration_reverse: 2.5
+ max_accelerator_power:
+ - 0.0
+ - 5000.0
+ max_accelerator_power_reverse: 5000.0
+ max_brake_deceleration: 8.0
+ pedal_mapping_function: linear
+ velocity_scaling_factor: 0.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/gem/racing2/src/GEMstack/GEMstack/knowledge/vehicle/model/gem_e4.urdf
+ wheel_radius: 0.33
+ wheelbase: 2.56
+ width: 1.7
+ limits:
+ max_acceleration: 3.0
+ max_accelerator_pedal: 1.0
+ max_brake_pedal: 1.0
+ max_deceleration: 5.0
+ max_reverse_speed: 2.5
+ max_speed: 10.0
+ max_steering_rate: 4.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/testing/racing_logs/launch_control_2/PurePursuitTrajectoryTracker_debug.csv b/testing/racing_logs/launch_control_2/PurePursuitTrajectoryTracker_debug.csv
new file mode 100644
index 000000000..294df95a3
--- /dev/null
+++ b/testing/racing_logs/launch_control_2/PurePursuitTrajectoryTracker_debug.csv
@@ -0,0 +1,767 @@
+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)
+1744061305.7372105,0.10138988494873047,0.0,1744061305.7372146,0.10138988494873047,0.0,1744061305.7372184,0.10138988494873047,2e-06,1744061305.7372224,0.10138988494873047,-56568542383.59379,1744061305.7372248,0.10138988494873047,0.065,1744061305.7372289,0.10138988494873047,3.1415926535886443,1744061305.7372303,0.10138988494873047,0.0649961945703726,1744061305.7372506,0.10138988494873047,9.359452054973492e-23,1744061305.7372518,0.10138988494873047,2.373329392326614,1744061305.7372537,0.10138988494873047,0.0,1744061305.737255,0.10138988494873047,-22627416996.07086,1744061305.7372565,0.10138988494873047,0.0,1744061305.7372577,0.10138988494873047,28284271247.461903
+1744061305.7549136,0.12147903442382812,0.0,1744061305.7549155,0.12147903442382812,0.0,1744061305.754918,0.12147903442382812,2e-06,1744061305.7549202,0.12147903442382812,-56568542383.59379,1744061305.7549214,0.12147903442382812,0.065,1744061305.754923,0.12147903442382812,3.1415926535886443,1744061305.7549243,0.12147903442382812,0.0649961945703726,1744061305.7549253,0.12147903442382812,9.359452054973492e-23,1744061305.7549264,0.12147903442382812,2.373329392326614,1744061305.7549279,0.12147903442382812,0.0,1744061305.754929,0.12147903442382812,-22627416996.07086,1744061305.7549305,0.12147903442382812,0.0,1744061305.7549314,0.12147903442382812,28284271247.461903
+1744061305.774712,0.14145946502685547,0.0,1744061305.7747145,0.14145946502685547,0.0,1744061305.7747169,0.14145946502685547,2e-06,1744061305.7747192,0.14145946502685547,-56568542383.59379,1744061305.7747204,0.14145946502685547,0.065,1744061305.774722,0.14145946502685547,3.1415926535886443,1744061305.774723,0.14145946502685547,0.0649961945703726,1744061305.7747242,0.14145946502685547,9.359452054973492e-23,1744061305.7747254,0.14145946502685547,2.373329392326614,1744061305.774727,0.14145946502685547,0.0,1744061305.7747283,0.14145946502685547,-22627416996.07086,1744061305.7747295,0.14145946502685547,0.0,1744061305.7747304,0.14145946502685547,28284271247.461903
+1744061305.7947462,0.16149473190307617,0.0,1744061305.794748,0.16149473190307617,0.0,1744061305.794751,0.16149473190307617,2e-06,1744061305.7947533,0.16149473190307617,-56568542383.59379,1744061305.7947545,0.16149473190307617,0.065,1744061305.794756,0.16149473190307617,3.1415926535886443,1744061305.7947571,0.16149473190307617,0.0649961945703726,1744061305.794758,0.16149473190307617,9.359452054973492e-23,1744061305.7947595,0.16149473190307617,2.373329392326614,1744061305.794761,0.16149473190307617,0.0,1744061305.794762,0.16149473190307617,-22627416996.07086,1744061305.7947633,0.16149473190307617,0.0,1744061305.7947645,0.16149473190307617,28284271247.461903
+1744061305.8146465,0.18148517608642578,0.0,1744061305.8146486,0.18148517608642578,0.0,1744061305.8146513,0.18148517608642578,2e-06,1744061305.8146534,0.18148517608642578,-56568542383.59379,1744061305.814655,0.18148517608642578,0.065,1744061305.8146563,0.18148517608642578,3.1415926535886443,1744061305.8146574,0.18148517608642578,0.0649961945703726,1744061305.8146589,0.18148517608642578,9.359452054973492e-23,1744061305.8146598,0.18148517608642578,2.373329392326614,1744061305.814661,0.18148517608642578,0.0,1744061305.8146625,0.18148517608642578,-22627416996.07086,1744061305.8146634,0.18148517608642578,0.0,1744061305.8146644,0.18148517608642578,28284271247.461903
+1744061305.8349724,0.2014625072479248,0.018067741594436883,1744061305.8349743,0.2014625072479248,-0.0005530614975234258,1744061305.8349764,0.2014625072479248,0.0022131675419837455,1744061305.8349786,0.2014625072479248,-56568542383.596,1744061305.8349795,0.2014625072479248,0.065,1744061305.8349812,0.2014625072479248,3.1415926535886345,1744061305.8349822,0.2014625072479248,0.0655488671147651,1744061305.834983,0.2014625072479248,9.439036901672498e-23,1744061305.8349845,0.2014625072479248,2.3722802850736633,1744061305.8349857,0.2014625072479248,0.0,1744061305.8349867,0.2014625072479248,-22627416996.072014,1744061305.834988,0.2014625072479248,0.0,1744061305.834989,0.2014625072479248,28284271247.461903
+1744061305.854899,0.22149991989135742,0.018067741594436883,1744061305.854901,0.22149991989135742,-0.0005530614975234258,1744061305.8549032,0.22149991989135742,0.0022131675419837455,1744061305.8549056,0.22149991989135742,-56568542383.596,1744061305.8549068,0.22149991989135742,0.065,1744061305.8549085,0.22149991989135742,3.1415926535886345,1744061305.8549097,0.22149991989135742,0.0655488671147651,1744061305.8549106,0.22149991989135742,9.439036901672498e-23,1744061305.8549118,0.22149991989135742,2.3722802850736633,1744061305.8549132,0.22149991989135742,0.0,1744061305.8549142,0.22149991989135742,-22627416996.0717,1744061305.8549156,0.22149991989135742,0.0,1744061305.8549166,0.22149991989135742,28284271247.461903
+1744061305.8746865,0.24145126342773438,0.018067741594436883,1744061305.8746896,0.24145126342773438,-0.0005530614975234258,1744061305.874693,0.24145126342773438,0.0022131675419837455,1744061305.8746965,0.24145126342773438,-56568542383.596,1744061305.8746982,0.24145126342773438,0.065,1744061305.8747005,0.24145126342773438,3.1415926535886345,1744061305.874703,0.24145126342773438,0.0655488671147651,1744061305.8747044,0.24145126342773438,9.439036901672498e-23,1744061305.8747065,0.24145126342773438,2.3722802850736633,1744061305.8747087,0.24145126342773438,0.0,1744061305.8747106,0.24145126342773438,-22627416996.0717,1744061305.874713,0.24145126342773438,0.0,1744061305.8747146,0.24145126342773438,28284271247.461903
+1744061305.8947964,0.261486291885376,0.018067741594436883,1744061305.8947983,0.261486291885376,-0.0005530614975234258,1744061305.8948007,0.261486291885376,0.0022131675419837455,1744061305.894803,0.261486291885376,-56568542383.596,1744061305.8948042,0.261486291885376,0.065,1744061305.894806,0.261486291885376,3.1415926535886345,1744061305.894807,0.261486291885376,0.0655488671147651,1744061305.894808,0.261486291885376,9.439036901672498e-23,1744061305.8948092,0.261486291885376,2.3722802850736633,1744061305.8948112,0.261486291885376,0.0,1744061305.894812,0.261486291885376,-22627416996.0717,1744061305.894814,0.261486291885376,0.0,1744061305.8948152,0.261486291885376,28284271247.461903
+1744061305.914596,0.2814502716064453,0.018067741594436883,1744061305.9145982,0.2814502716064453,-0.0005530614975234258,1744061305.9146004,0.2814502716064453,0.0022131675419837455,1744061305.9146025,0.2814502716064453,-56568542383.596,1744061305.9146035,0.2814502716064453,0.065,1744061305.914605,0.2814502716064453,3.1415926535886345,1744061305.914606,0.2814502716064453,0.0655488671147651,1744061305.914607,0.2814502716064453,9.439036901672498e-23,1744061305.9146082,0.2814502716064453,2.3722802850736633,1744061305.9146094,0.2814502716064453,0.0,1744061305.9146104,0.2814502716064453,-22627416996.0717,1744061305.9146118,0.2814502716064453,0.0,1744061305.914613,0.2814502716064453,28284271247.461903
+1744061305.934942,0.30145859718322754,0.018067741594436883,1744061305.9349437,0.30145859718322754,-0.0005530614975234258,1744061305.934946,0.30145859718322754,0.0022131675419837455,1744061305.9349482,0.30145859718322754,-56568542383.596,1744061305.9349494,0.30145859718322754,0.065,1744061305.9349506,0.30145859718322754,3.1415926535886345,1744061305.9349518,0.30145859718322754,0.0655488671147651,1744061305.9349527,0.30145859718322754,9.439036901672498e-23,1744061305.9349537,0.30145859718322754,2.3722802850736633,1744061305.9349551,0.30145859718322754,0.0,1744061305.934956,0.30145859718322754,-22627416996.0717,1744061305.9349573,0.30145859718322754,0.0,1744061305.9349582,0.30145859718322754,28284271247.461903
+1744061305.9550755,0.321519136428833,0.018067741594436883,1744061305.9550776,0.321519136428833,-0.0005530614975234258,1744061305.95508,0.321519136428833,0.0022131675419837455,1744061305.955082,0.321519136428833,-56568542383.596,1744061305.9550834,0.321519136428833,0.065,1744061305.9550846,0.321519136428833,3.1415926535886345,1744061305.9550858,0.321519136428833,0.0655488671147651,1744061305.955087,0.321519136428833,9.439036901672498e-23,1744061305.955088,0.321519136428833,2.3722802850736633,1744061305.9550893,0.321519136428833,0.0,1744061305.9550905,0.321519136428833,-22627416996.0717,1744061305.9550917,0.321519136428833,0.0,1744061305.9550927,0.321519136428833,28284271247.461903
+1744061305.9746876,0.34145355224609375,0.018067741594436883,1744061305.9746895,0.34145355224609375,-0.0005530614975234258,1744061305.9746919,0.34145355224609375,0.0022131675419837455,1744061305.9746943,0.34145355224609375,-56568542383.596,1744061305.9746954,0.34145355224609375,0.065,1744061305.9746966,0.34145355224609375,3.1415926535886345,1744061305.974698,0.34145355224609375,0.0655488671147651,1744061305.974699,0.34145355224609375,9.439036901672498e-23,1744061305.9747,0.34145355224609375,2.3722802850736633,1744061305.974702,0.34145355224609375,0.0,1744061305.9747028,0.34145355224609375,-22627416996.0717,1744061305.974704,0.34145355224609375,0.0,1744061305.9747055,0.34145355224609375,28284271247.461903
+1744061305.995114,0.3618018627166748,0.018067741594436883,1744061305.995116,0.3618018627166748,-0.0005530614975234258,1744061305.9951181,0.3618018627166748,0.0022131675419837455,1744061305.9951203,0.3618018627166748,-56568542383.596,1744061305.9951215,0.3618018627166748,0.065,1744061305.9951227,0.3618018627166748,3.1415926535886345,1744061305.9951239,0.3618018627166748,0.0655488671147651,1744061305.995125,0.3618018627166748,9.439036901672498e-23,1744061305.995126,0.3618018627166748,2.3722802850736633,1744061305.9951272,0.3618018627166748,0.0,1744061305.9951284,0.3618018627166748,-22627416996.0717,1744061305.9951296,0.3618018627166748,0.0,1744061305.9951305,0.3618018627166748,28284271247.461903
+1744061306.0150404,0.38145899772644043,0.018067741594436883,1744061306.0150425,0.38145899772644043,-0.0005530614975234258,1744061306.0150452,0.38145899772644043,0.0022131675419837455,1744061306.0150473,0.38145899772644043,-56568542383.596,1744061306.0150485,0.38145899772644043,0.065,1744061306.01505,0.38145899772644043,3.1415926535886345,1744061306.0150514,0.38145899772644043,0.0655488671147651,1744061306.0150523,0.38145899772644043,9.439036901672498e-23,1744061306.0150533,0.38145899772644043,2.3722802850736633,1744061306.015055,0.38145899772644043,0.0,1744061306.0150561,0.38145899772644043,-22627416996.0717,1744061306.0150573,0.38145899772644043,0.0,1744061306.0150585,0.38145899772644043,28284271247.461903
+1744061306.0357838,0.4014873504638672,0.018067741594436883,1744061306.0357862,0.4014873504638672,-0.0005530614975234258,1744061306.0357885,0.4014873504638672,0.0022131675419837455,1744061306.0357907,0.4014873504638672,-56568542383.596,1744061306.0357919,0.4014873504638672,0.065,1744061306.0357928,0.4014873504638672,3.1415926535886345,1744061306.0357943,0.4014873504638672,0.0655488671147651,1744061306.0357952,0.4014873504638672,9.439036901672498e-23,1744061306.0357962,0.4014873504638672,2.3722802850736633,1744061306.0357978,0.4014873504638672,0.0,1744061306.0357988,0.4014873504638672,-22627416996.0717,1744061306.0357997,0.4014873504638672,0.0,1744061306.0358012,0.4014873504638672,28284271247.461903
+1744061306.0553412,0.4214622974395752,0.018067741594436883,1744061306.0553439,0.4214622974395752,-0.0005530614975234258,1744061306.0553465,0.4214622974395752,0.0022131675419837455,1744061306.0553484,0.4214622974395752,-56568542383.596,1744061306.0553498,0.4214622974395752,0.065,1744061306.0553513,0.4214622974395752,3.1415926535886345,1744061306.0553527,0.4214622974395752,0.0655488671147651,1744061306.0553536,0.4214622974395752,9.439036901672498e-23,1744061306.0553546,0.4214622974395752,2.3722802850736633,1744061306.0553563,0.4214622974395752,0.0,1744061306.0553575,0.4214622974395752,-22627416996.0717,1744061306.0553584,0.4214622974395752,0.0,1744061306.0553596,0.4214622974395752,28284271247.461903
+1744061306.074798,0.44147491455078125,0.018067741594436883,1744061306.0748,0.44147491455078125,-0.0005530614975234258,1744061306.0748024,0.44147491455078125,0.0022131675419837455,1744061306.0748048,0.44147491455078125,-56568542383.596,1744061306.074806,0.44147491455078125,0.065,1744061306.0748076,0.44147491455078125,3.1415926535886345,1744061306.0748086,0.44147491455078125,0.0655488671147651,1744061306.0748096,0.44147491455078125,9.439036901672498e-23,1744061306.0748105,0.44147491455078125,2.3722802850736633,1744061306.074812,0.44147491455078125,0.0,1744061306.074813,0.44147491455078125,-22627416996.0717,1744061306.0748146,0.44147491455078125,0.0,1744061306.0748155,0.44147491455078125,28284271247.461903
+1744061306.094956,0.46150827407836914,0.018067741594436883,1744061306.094958,0.46150827407836914,-0.0005530614975234258,1744061306.0949607,0.46150827407836914,0.0022131675419837455,1744061306.0949626,0.46150827407836914,-56568542383.596,1744061306.094964,0.46150827407836914,0.065,1744061306.0949652,0.46150827407836914,3.1415926535886345,1744061306.0949664,0.46150827407836914,0.0655488671147651,1744061306.0949676,0.46150827407836914,9.439036901672498e-23,1744061306.0949686,0.46150827407836914,2.3722802850736633,1744061306.0949702,0.46150827407836914,0.0,1744061306.0949712,0.46150827407836914,-22627416996.0717,1744061306.0949721,0.46150827407836914,0.0,1744061306.094973,0.46150827407836914,28284271247.461903
+1744061306.1148777,0.48145318031311035,0.018067741594436883,1744061306.1148798,0.48145318031311035,-0.0005530614975234258,1744061306.1148822,0.48145318031311035,0.0022131675419837455,1744061306.1148844,0.48145318031311035,-56568542383.596,1744061306.1148856,0.48145318031311035,0.065,1744061306.114887,0.48145318031311035,3.1415926535886345,1744061306.114888,0.48145318031311035,0.0655488671147651,1744061306.114889,0.48145318031311035,9.439036901672498e-23,1744061306.11489,0.48145318031311035,2.3722802850736633,1744061306.1148915,0.48145318031311035,0.0,1744061306.1148925,0.48145318031311035,-22627416996.0717,1744061306.1148937,0.48145318031311035,0.0,1744061306.1148946,0.48145318031311035,28284271247.461903
+1744061306.134989,0.5014503002166748,0.018067741594436883,1744061306.1349912,0.5014503002166748,-0.0005530614975234258,1744061306.1349933,0.5014503002166748,0.0022131675419837455,1744061306.1349955,0.5014503002166748,-56568542383.596,1744061306.1349964,0.5014503002166748,0.065,1744061306.1349978,0.5014503002166748,3.1415926535886345,1744061306.1349988,0.5014503002166748,0.0655488671147651,1744061306.1349998,0.5014503002166748,9.439036901672498e-23,1744061306.135001,0.5014503002166748,2.3722802850736633,1744061306.1350021,0.5014503002166748,0.0,1744061306.135003,0.5014503002166748,-22627416996.0717,1744061306.135004,0.5014503002166748,0.0,1744061306.1350052,0.5014503002166748,28284271247.461903
+1744061306.1554468,0.5214667320251465,0.018067741594436883,1744061306.1554503,0.5214667320251465,-0.0005530614975234258,1744061306.1554544,0.5214667320251465,0.0022131675419837455,1744061306.1554582,0.5214667320251465,-56568542383.596,1744061306.1554604,0.5214667320251465,0.065,1744061306.155463,0.5214667320251465,3.1415926535886345,1744061306.1554651,0.5214667320251465,0.0655488671147651,1744061306.1554675,0.5214667320251465,9.439036901672498e-23,1744061306.1554697,0.5214667320251465,2.3722802850736633,1744061306.155473,0.5214667320251465,0.0,1744061306.1554751,0.5214667320251465,-22627416996.0717,1744061306.1554775,0.5214667320251465,0.0,1744061306.1554797,0.5214667320251465,28284271247.461903
+1744061306.174996,0.5414566993713379,0.018067741594436883,1744061306.1749988,0.5414566993713379,-0.0005530614975234258,1744061306.175002,0.5414566993713379,0.0022131675419837455,1744061306.1750057,0.5414566993713379,-56568542383.596,1744061306.1750078,0.5414566993713379,0.065,1744061306.1750102,0.5414566993713379,3.1415926535886345,1744061306.1750126,0.5414566993713379,0.0655488671147651,1744061306.1750145,0.5414566993713379,9.439036901672498e-23,1744061306.1750166,0.5414566993713379,2.3722802850736633,1744061306.175019,0.5414566993713379,0.0,1744061306.1750212,0.5414566993713379,-22627416996.0717,1744061306.1750236,0.5414566993713379,0.0,1744061306.1750257,0.5414566993713379,28284271247.461903
+1744061306.1950452,0.5615196228027344,0.018067741594436883,1744061306.1950471,0.5615196228027344,-0.0005530614975234258,1744061306.1950498,0.5615196228027344,0.0022131675419837455,1744061306.1950517,0.5615196228027344,-56568542383.596,1744061306.195053,0.5615196228027344,0.065,1744061306.1950543,0.5615196228027344,3.1415926535886345,1744061306.1950557,0.5615196228027344,0.0655488671147651,1744061306.1950567,0.5615196228027344,9.439036901672498e-23,1744061306.1950576,0.5615196228027344,2.3722802850736633,1744061306.1950593,0.5615196228027344,0.0,1744061306.1950605,0.5615196228027344,-22627416996.0717,1744061306.1950614,0.5615196228027344,0.0,1744061306.1950626,0.5615196228027344,28284271247.461903
+1744061306.2147553,0.5814590454101562,0.018067741594436883,1744061306.2147574,0.5814590454101562,-0.0005530614975234258,1744061306.2147596,0.5814590454101562,0.0022131675419837455,1744061306.2147617,0.5814590454101562,-56568542383.596,1744061306.214763,0.5814590454101562,0.065,1744061306.2147646,0.5814590454101562,3.1415926535886345,1744061306.2147655,0.5814590454101562,0.0655488671147651,1744061306.2147665,0.5814590454101562,9.439036901672498e-23,1744061306.2147677,0.5814590454101562,2.3722802850736633,1744061306.214769,0.5814590454101562,0.0,1744061306.2147698,0.5814590454101562,-22627416996.0717,1744061306.2147713,0.5814590454101562,0.0,1744061306.2147722,0.5814590454101562,28284271247.461903
+1744061306.2353055,0.6014480590820312,0.018067741594436883,1744061306.2353077,0.6014480590820312,-0.0005530614975234258,1744061306.2353108,0.6014480590820312,0.0022131675419837455,1744061306.2353132,0.6014480590820312,-56568542383.596,1744061306.2353146,0.6014480590820312,0.065,1744061306.2353165,0.6014480590820312,3.1415926535886345,1744061306.2353177,0.6014480590820312,0.0655488671147651,1744061306.235319,0.6014480590820312,9.439036901672498e-23,1744061306.23532,0.6014480590820312,2.3722802850736633,1744061306.2353272,0.6014480590820312,0.0,1744061306.2353287,0.6014480590820312,-22627416996.0717,1744061306.23533,0.6014480590820312,0.0,1744061306.2353313,0.6014480590820312,28284271247.461903
+1744061306.2562997,0.6214852333068848,0.018067741594436883,1744061306.2563076,0.6214852333068848,-0.0005530614975234258,1744061306.2563157,0.6214852333068848,0.0022131675419837455,1744061306.2563193,0.6214852333068848,-56568542383.596,1744061306.2563214,0.6214852333068848,0.065,1744061306.256324,0.6214852333068848,3.1415926535886345,1744061306.2563264,0.6214852333068848,0.0655488671147651,1744061306.2563279,0.6214852333068848,9.439036901672498e-23,1744061306.2563305,0.6214852333068848,2.3722802850736633,1744061306.256335,0.6214852333068848,0.0,1744061306.2563381,0.6214852333068848,-22627416996.0717,1744061306.256342,0.6214852333068848,0.0,1744061306.2563457,0.6214852333068848,28284271247.461903
+1744061306.2749684,0.6414709091186523,0.018067741594436883,1744061306.2749703,0.6414709091186523,-0.0005530614975234258,1744061306.274973,0.6414709091186523,0.0022131675419837455,1744061306.2749753,0.6414709091186523,-56568542383.596,1744061306.2749763,0.6414709091186523,0.065,1744061306.2749774,0.6414709091186523,3.1415926535886345,1744061306.2749789,0.6414709091186523,0.0655488671147651,1744061306.2749798,0.6414709091186523,9.439036901672498e-23,1744061306.2749808,0.6414709091186523,2.3722802850736633,1744061306.2749827,0.6414709091186523,0.0,1744061306.274984,0.6414709091186523,-22627416996.0717,1744061306.2749853,0.6414709091186523,0.0,1744061306.2749863,0.6414709091186523,28284271247.461903
+1744061306.2947888,0.6614851951599121,0.018067741594436883,1744061306.294791,0.6614851951599121,-0.0005530614975234258,1744061306.2947931,0.6614851951599121,0.0022131675419837455,1744061306.2947953,0.6614851951599121,-56568542383.596,1744061306.2947967,0.6614851951599121,0.065,1744061306.2947984,0.6614851951599121,3.1415926535886345,1744061306.2947993,0.6614851951599121,0.0655488671147651,1744061306.2948003,0.6614851951599121,9.439036901672498e-23,1744061306.2948015,0.6614851951599121,2.3722802850736633,1744061306.294803,0.6614851951599121,0.0,1744061306.2948039,0.6614851951599121,-22627416996.0717,1744061306.294805,0.6614851951599121,0.0,1744061306.294806,0.6614851951599121,28284271247.461903
+1744061306.3147392,0.681452751159668,0.018067741594436883,1744061306.314741,0.681452751159668,-0.0005530614975234258,1744061306.3147433,0.681452751159668,0.0022131675419837455,1744061306.3147457,0.681452751159668,-56568542383.596,1744061306.3147469,0.681452751159668,0.065,1744061306.3147485,0.681452751159668,3.1415926535886345,1744061306.3147495,0.681452751159668,0.0655488671147651,1744061306.3147504,0.681452751159668,9.439036901672498e-23,1744061306.3147514,0.681452751159668,2.3722802850736633,1744061306.314753,0.681452751159668,0.0,1744061306.3147542,0.681452751159668,-22627416996.0717,1744061306.3147554,0.681452751159668,0.0,1744061306.3147564,0.681452751159668,28284271247.461903
+1744061306.3350852,0.7014517784118652,0.03340549242316977,1744061306.3350868,0.7014517784118652,-0.0005154131843987907,1744061306.3350892,0.7014517784118652,0.021580542763179292,1744061306.3350914,0.7014517784118652,-56568542383.61537,1744061306.3350925,0.7014517784118652,0.065,1744061306.335094,0.7014517784118652,3.141592653588635,1744061306.335095,0.7014517784118652,0.0655237456355158,1744061306.3350961,0.7014517784118652,9.435419408634783e-23,1744061306.335097,0.7014517784118652,2.372327961704709,1744061306.335099,0.7014517784118652,0.0,1744061306.3351,0.7014517784118652,-22627416996.071644,1744061306.335101,0.7014517784118652,0.0,1744061306.3351018,0.7014517784118652,28284271247.461903
+1744061306.3558156,0.7215256690979004,0.03340549242316977,1744061306.3558197,0.7215256690979004,-0.0005154131843987907,1744061306.3558226,0.7215256690979004,0.021580542763179292,1744061306.355825,0.7215256690979004,-56568542383.61537,1744061306.3558264,0.7215256690979004,0.065,1744061306.3558283,0.7215256690979004,3.141592653588635,1744061306.3558302,0.7215256690979004,0.0655237456355158,1744061306.3558314,0.7215256690979004,9.435419408634783e-23,1744061306.3558328,0.7215256690979004,2.372327961704709,1744061306.3558354,0.7215256690979004,0.0,1744061306.3558366,0.7215256690979004,-22627416996.07166,1744061306.3558383,0.7215256690979004,0.0,1744061306.3558395,0.7215256690979004,28284271247.461903
+1744061306.3759956,0.741769552230835,0.03340549242316977,1744061306.3760037,0.741769552230835,-0.0005154131843987907,1744061306.3760066,0.741769552230835,0.021580542763179292,1744061306.376009,0.741769552230835,-56568542383.61537,1744061306.3760104,0.741769552230835,0.065,1744061306.376012,0.741769552230835,3.141592653588635,1744061306.3760133,0.741769552230835,0.0655237456355158,1744061306.3760142,0.741769552230835,9.435419408634783e-23,1744061306.3760154,0.741769552230835,2.372327961704709,1744061306.376017,0.741769552230835,0.0,1744061306.3760183,0.741769552230835,-22627416996.07166,1744061306.3760192,0.741769552230835,0.0,1744061306.3760204,0.741769552230835,28284271247.461903
+1744061306.3947554,0.7614850997924805,0.03340549242316977,1744061306.3947573,0.7614850997924805,-0.0005154131843987907,1744061306.39476,0.7614850997924805,0.021580542763179292,1744061306.394762,0.7614850997924805,-56568542383.61537,1744061306.3947632,0.7614850997924805,0.065,1744061306.3947647,0.7614850997924805,3.141592653588635,1744061306.3947656,0.7614850997924805,0.0655237456355158,1744061306.3947666,0.7614850997924805,9.435419408634783e-23,1744061306.3947675,0.7614850997924805,2.372327961704709,1744061306.3947694,0.7614850997924805,0.0,1744061306.3947704,0.7614850997924805,-22627416996.07166,1744061306.3947718,0.7614850997924805,0.0,1744061306.3947728,0.7614850997924805,28284271247.461903
+1744061306.4147723,0.7814717292785645,0.03340549242316977,1744061306.4147742,0.7814717292785645,-0.0005154131843987907,1744061306.4147766,0.7814717292785645,0.021580542763179292,1744061306.4147787,0.7814717292785645,-56568542383.61537,1744061306.41478,0.7814717292785645,0.065,1744061306.4147813,0.7814717292785645,3.141592653588635,1744061306.4147825,0.7814717292785645,0.0655237456355158,1744061306.4147835,0.7814717292785645,9.435419408634783e-23,1744061306.4147847,0.7814717292785645,2.372327961704709,1744061306.4147866,0.7814717292785645,0.0,1744061306.4147875,0.7814717292785645,-22627416996.07166,1744061306.414798,0.7814717292785645,0.0,1744061306.4147997,0.7814717292785645,28284271247.461903
+1744061306.43551,0.8014638423919678,0.03340549242316977,1744061306.4355133,0.8014638423919678,-0.0005154131843987907,1744061306.4355156,0.8014638423919678,0.021580542763179292,1744061306.435518,0.8014638423919678,-56568542383.61537,1744061306.4355195,0.8014638423919678,0.065,1744061306.4355214,0.8014638423919678,3.141592653588635,1744061306.4355226,0.8014638423919678,0.0655237456355158,1744061306.4355235,0.8014638423919678,9.435419408634783e-23,1744061306.435525,0.8014638423919678,2.372327961704709,1744061306.4355264,0.8014638423919678,0.0,1744061306.4355273,0.8014638423919678,-22627416996.07166,1744061306.4355288,0.8014638423919678,0.0,1744061306.4355297,0.8014638423919678,28284271247.461903
+1744061306.4548452,0.821460485458374,0.03340549242316977,1744061306.4548473,0.821460485458374,-0.0005154131843987907,1744061306.4548495,0.821460485458374,0.021580542763179292,1744061306.4548516,0.821460485458374,-56568542383.61537,1744061306.4548528,0.821460485458374,0.065,1744061306.4548542,0.821460485458374,3.141592653588635,1744061306.4548554,0.821460485458374,0.0655237456355158,1744061306.4548564,0.821460485458374,9.435419408634783e-23,1744061306.4548576,0.821460485458374,2.372327961704709,1744061306.4548593,0.821460485458374,0.0,1744061306.4548602,0.821460485458374,-22627416996.07166,1744061306.4548616,0.821460485458374,0.0,1744061306.4548626,0.821460485458374,28284271247.461903
+1744061306.4749491,0.8414516448974609,0.03340549242316977,1744061306.4749517,0.8414516448974609,-0.0005154131843987907,1744061306.4749537,0.8414516448974609,0.021580542763179292,1744061306.4749558,0.8414516448974609,-56568542383.61537,1744061306.474957,0.8414516448974609,0.065,1744061306.4749587,0.8414516448974609,3.141592653588635,1744061306.4749596,0.8414516448974609,0.0655237456355158,1744061306.4749606,0.8414516448974609,9.435419408634783e-23,1744061306.4749618,0.8414516448974609,2.372327961704709,1744061306.4749634,0.8414516448974609,0.0,1744061306.4749644,0.8414516448974609,-22627416996.07166,1744061306.4749658,0.8414516448974609,0.0,1744061306.4749668,0.8414516448974609,28284271247.461903
+1744061306.4952154,0.8614950180053711,0.03340549242316977,1744061306.4952188,0.8614950180053711,-0.0005154131843987907,1744061306.4952402,0.8614950180053711,0.021580542763179292,1744061306.495243,0.8614950180053711,-56568542383.61537,1744061306.4952447,0.8614950180053711,0.065,1744061306.4952464,0.8614950180053711,3.141592653588635,1744061306.4952478,0.8614950180053711,0.0655237456355158,1744061306.4952488,0.8614950180053711,9.435419408634783e-23,1744061306.4952502,0.8614950180053711,2.372327961704709,1744061306.4952521,0.8614950180053711,0.0,1744061306.4952536,0.8614950180053711,-22627416996.07166,1744061306.495255,0.8614950180053711,0.0,1744061306.4952567,0.8614950180053711,28284271247.461903
+1744061306.5147395,0.8814659118652344,0.03340549242316977,1744061306.5147414,0.8814659118652344,-0.0005154131843987907,1744061306.5147438,0.8814659118652344,0.021580542763179292,1744061306.5147462,0.8814659118652344,-56568542383.61537,1744061306.5147474,0.8814659118652344,0.065,1744061306.5147486,0.8814659118652344,3.141592653588635,1744061306.51475,0.8814659118652344,0.0655237456355158,1744061306.5147507,0.8814659118652344,9.435419408634783e-23,1744061306.514752,0.8814659118652344,2.372327961704709,1744061306.5147533,0.8814659118652344,0.0,1744061306.5147545,0.8814659118652344,-22627416996.07166,1744061306.5147555,0.8814659118652344,0.0,1744061306.5147567,0.8814659118652344,28284271247.461903
+1744061306.5353303,0.9014837741851807,0.03340549242316977,1744061306.5353324,0.9014837741851807,-0.0005154131843987907,1744061306.5353343,0.9014837741851807,0.021580542763179292,1744061306.5353367,0.9014837741851807,-56568542383.61537,1744061306.5353377,0.9014837741851807,0.065,1744061306.535339,0.9014837741851807,3.141592653588635,1744061306.5353403,0.9014837741851807,0.0655237456355158,1744061306.5353413,0.9014837741851807,9.435419408634783e-23,1744061306.5353425,0.9014837741851807,2.372327961704709,1744061306.5353436,0.9014837741851807,0.0,1744061306.5353446,0.9014837741851807,-22627416996.07166,1744061306.5353456,0.9014837741851807,0.0,1744061306.5353467,0.9014837741851807,28284271247.461903
+1744061306.5554433,0.9215342998504639,0.03340549242316977,1744061306.5554454,0.9215342998504639,-0.0005154131843987907,1744061306.5554476,0.9215342998504639,0.021580542763179292,1744061306.55545,0.9215342998504639,-56568542383.61537,1744061306.5554516,0.9215342998504639,0.065,1744061306.5554528,0.9215342998504639,3.141592653588635,1744061306.5554543,0.9215342998504639,0.0655237456355158,1744061306.5554552,0.9215342998504639,9.435419408634783e-23,1744061306.5554564,0.9215342998504639,2.372327961704709,1744061306.5554583,0.9215342998504639,0.0,1744061306.5554593,0.9215342998504639,-22627416996.07166,1744061306.5554607,0.9215342998504639,0.0,1744061306.5554616,0.9215342998504639,28284271247.461903
+1744061306.5754912,0.9414820671081543,0.03340549242316977,1744061306.5754962,0.9414820671081543,-0.0005154131843987907,1744061306.5755,0.9414820671081543,0.021580542763179292,1744061306.5755024,0.9414820671081543,-56568542383.61537,1744061306.575504,0.9414820671081543,0.065,1744061306.5755057,0.9414820671081543,3.141592653588635,1744061306.5755076,0.9414820671081543,0.0655237456355158,1744061306.575509,0.9414820671081543,9.435419408634783e-23,1744061306.57551,0.9414820671081543,2.372327961704709,1744061306.5755131,0.9414820671081543,0.0,1744061306.575514,0.9414820671081543,-22627416996.07166,1744061306.5755165,0.9414820671081543,0.0,1744061306.5755177,0.9414820671081543,28284271247.461903
+1744061306.5949092,0.961498498916626,0.03340549242316977,1744061306.5949113,0.961498498916626,-0.0005154131843987907,1744061306.5949135,0.961498498916626,0.021580542763179292,1744061306.5949159,0.961498498916626,-56568542383.61537,1744061306.5949168,0.961498498916626,0.065,1744061306.5949185,0.961498498916626,3.141592653588635,1744061306.5949197,0.961498498916626,0.0655237456355158,1744061306.5949204,0.961498498916626,9.435419408634783e-23,1744061306.5949218,0.961498498916626,2.372327961704709,1744061306.594924,0.961498498916626,0.0,1744061306.5949259,0.961498498916626,-22627416996.07166,1744061306.594927,0.961498498916626,0.0,1744061306.594928,0.961498498916626,28284271247.461903
+1744061306.6146348,0.9814825057983398,0.03340549242316977,1744061306.614637,0.9814825057983398,-0.0005154131843987907,1744061306.6146388,0.9814825057983398,0.021580542763179292,1744061306.6146412,0.9814825057983398,-56568542383.61537,1744061306.6146424,0.9814825057983398,0.065,1744061306.6146438,0.9814825057983398,3.141592653588635,1744061306.614645,0.9814825057983398,0.0655237456355158,1744061306.6146457,0.9814825057983398,9.435419408634783e-23,1744061306.6146472,0.9814825057983398,2.372327961704709,1744061306.6146483,0.9814825057983398,0.0,1744061306.6146495,0.9814825057983398,-22627416996.07166,1744061306.6146507,0.9814825057983398,0.0,1744061306.6146517,0.9814825057983398,28284271247.461903
+1744061306.6349661,1.001460075378418,0.03340549242316977,1744061306.6349678,1.001460075378418,-0.0005154131843987907,1744061306.6349702,1.001460075378418,0.021580542763179292,1744061306.6349723,1.001460075378418,-56568542383.61537,1744061306.6349735,1.001460075378418,0.065,1744061306.634975,1.001460075378418,3.141592653588635,1744061306.634976,1.001460075378418,0.0655237456355158,1744061306.634977,1.001460075378418,9.435419408634783e-23,1744061306.634978,1.001460075378418,2.372327961704709,1744061306.6349792,1.001460075378418,0.0,1744061306.6349804,1.001460075378418,-22627416996.07166,1744061306.6349814,1.001460075378418,0.0,1744061306.6349826,1.001460075378418,28284271247.461903
+1744061306.6552415,1.0214917659759521,0.03340549242316977,1744061306.6552439,1.0214917659759521,-0.0005154131843987907,1744061306.6552465,1.0214917659759521,0.021580542763179292,1744061306.655249,1.0214917659759521,-56568542383.61537,1744061306.6552505,1.0214917659759521,0.065,1744061306.655252,1.0214917659759521,3.141592653588635,1744061306.6552532,1.0214917659759521,0.0655237456355158,1744061306.6552546,1.0214917659759521,9.435419408634783e-23,1744061306.6552558,1.0214917659759521,2.372327961704709,1744061306.6552577,1.0214917659759521,0.0,1744061306.6552587,1.0214917659759521,-22627416996.07166,1744061306.6552598,1.0214917659759521,0.0,1744061306.655261,1.0214917659759521,28284271247.461903
+1744061306.6747863,1.0414955615997314,0.03340549242316977,1744061306.674788,1.0414955615997314,-0.0005154131843987907,1744061306.6747904,1.0414955615997314,0.021580542763179292,1744061306.6747925,1.0414955615997314,-56568542383.61537,1744061306.6747937,1.0414955615997314,0.065,1744061306.674795,1.0414955615997314,3.141592653588635,1744061306.674796,1.0414955615997314,0.0655237456355158,1744061306.674797,1.0414955615997314,9.435419408634783e-23,1744061306.674798,1.0414955615997314,2.372327961704709,1744061306.6747997,1.0414955615997314,0.0,1744061306.6748006,1.0414955615997314,-22627416996.07166,1744061306.6748018,1.0414955615997314,0.0,1744061306.674803,1.0414955615997314,28284271247.461903
+1744061306.6947157,1.0614848136901855,0.03340549242316977,1744061306.6947176,1.0614848136901855,-0.0005154131843987907,1744061306.69472,1.0614848136901855,0.021580542763179292,1744061306.6947224,1.0614848136901855,-56568542383.61537,1744061306.6947234,1.0614848136901855,0.065,1744061306.6947246,1.0614848136901855,3.141592653588635,1744061306.694726,1.0614848136901855,0.0655237456355158,1744061306.694727,1.0614848136901855,9.435419408634783e-23,1744061306.694728,1.0614848136901855,2.372327961704709,1744061306.6947298,1.0614848136901855,0.0,1744061306.6947308,1.0614848136901855,-22627416996.07166,1744061306.694732,1.0614848136901855,0.0,1744061306.6947334,1.0614848136901855,28284271247.461903
+1744061306.7146742,1.0814943313598633,0.03340549242316977,1744061306.714676,1.0814943313598633,-0.0005154131843987907,1744061306.714678,1.0814943313598633,0.021580542763179292,1744061306.7146804,1.0814943313598633,-56568542383.61537,1744061306.7146814,1.0814943313598633,0.065,1744061306.7146828,1.0814943313598633,3.141592653588635,1744061306.714684,1.0814943313598633,0.0655237456355158,1744061306.714685,1.0814943313598633,9.435419408634783e-23,1744061306.714686,1.0814943313598633,2.372327961704709,1744061306.7146876,1.0814943313598633,0.0,1744061306.7146885,1.0814943313598633,-22627416996.07166,1744061306.7146895,1.0814943313598633,0.0,1744061306.7146904,1.0814943313598633,28284271247.461903
+1744061306.734894,1.101454257965088,0.03340549242316977,1744061306.734896,1.101454257965088,-0.0005154131843987907,1744061306.7348979,1.101454257965088,0.021580542763179292,1744061306.7349002,1.101454257965088,-56568542383.61537,1744061306.7349012,1.101454257965088,0.065,1744061306.7349029,1.101454257965088,3.141592653588635,1744061306.7349038,1.101454257965088,0.0655237456355158,1744061306.7349048,1.101454257965088,9.435419408634783e-23,1744061306.734906,1.101454257965088,2.372327961704709,1744061306.7349072,1.101454257965088,0.0,1744061306.734908,1.101454257965088,-22627416996.07166,1744061306.7349093,1.101454257965088,0.0,1744061306.7349102,1.101454257965088,28284271247.461903
+1744061306.7549531,1.1214559078216553,0.03340549242316977,1744061306.7549553,1.1214559078216553,-0.0005154131843987907,1744061306.754958,1.1214559078216553,0.021580542763179292,1744061306.7549603,1.1214559078216553,-56568542383.61537,1744061306.7549622,1.1214559078216553,0.065,1744061306.754964,1.1214559078216553,3.141592653588635,1744061306.7549658,1.1214559078216553,0.0655237456355158,1744061306.7549667,1.1214559078216553,9.435419408634783e-23,1744061306.7549686,1.1214559078216553,2.372327961704709,1744061306.754971,1.1214559078216553,0.0,1744061306.7549734,1.1214559078216553,-22627416996.07166,1744061306.754975,1.1214559078216553,0.0,1744061306.7549763,1.1214559078216553,28284271247.461903
+1744061306.7748454,1.141491413116455,0.03340549242316977,1744061306.7748473,1.141491413116455,-0.0005154131843987907,1744061306.7748497,1.141491413116455,0.021580542763179292,1744061306.7748516,1.141491413116455,-56568542383.61537,1744061306.7748525,1.141491413116455,0.065,1744061306.7748542,1.141491413116455,3.141592653588635,1744061306.7748554,1.141491413116455,0.0655237456355158,1744061306.7748563,1.141491413116455,9.435419408634783e-23,1744061306.7748575,1.141491413116455,2.372327961704709,1744061306.774859,1.141491413116455,0.0,1744061306.7748604,1.141491413116455,-22627416996.07166,1744061306.7748613,1.141491413116455,0.0,1744061306.7748623,1.141491413116455,28284271247.461903
+1744061306.794652,1.1614747047424316,0.03340549242316977,1744061306.7946537,1.1614747047424316,-0.0005154131843987907,1744061306.794656,1.1614747047424316,0.021580542763179292,1744061306.7946584,1.1614747047424316,-56568542383.61537,1744061306.7946594,1.1614747047424316,0.065,1744061306.7946606,1.1614747047424316,3.141592653588635,1744061306.794662,1.1614747047424316,0.0655237456355158,1744061306.7946627,1.1614747047424316,9.435419408634783e-23,1744061306.7946637,1.1614747047424316,2.372327961704709,1744061306.794665,1.1614747047424316,0.0,1744061306.7946663,1.1614747047424316,-22627416996.07166,1744061306.7946672,1.1614747047424316,0.0,1744061306.7946682,1.1614747047424316,28284271247.461903
+1744061306.8147664,1.1814489364624023,0.03340549242316977,1744061306.8147683,1.1814489364624023,-0.0005154131843987907,1744061306.8147707,1.1814489364624023,0.021580542763179292,1744061306.8147728,1.1814489364624023,-56568542383.61537,1744061306.8147738,1.1814489364624023,0.065,1744061306.8147752,1.1814489364624023,3.141592653588635,1744061306.8147767,1.1814489364624023,0.0655237456355158,1744061306.8147776,1.1814489364624023,9.435419408634783e-23,1744061306.8147786,1.1814489364624023,2.372327961704709,1744061306.81478,1.1814489364624023,0.0,1744061306.814781,1.1814489364624023,-22627416996.07166,1744061306.814782,1.1814489364624023,0.0,1744061306.8147829,1.1814489364624023,28284271247.461903
+1744061306.8353891,1.2015023231506348,0.041613443739632924,1744061306.8353913,1.2015023231506348,-0.0006556382546494058,1744061306.8353932,1.2015023231506348,0.021662622276343926,1744061306.8353956,1.2015023231506348,-56568542383.61545,1744061306.8353965,1.2015023231506348,0.065,1744061306.835398,1.2015023231506348,3.1415926535886327,1744061306.835399,1.2015023231506348,0.06564935303197303,1744061306.8353999,1.2015023231506348,9.453506873793015e-23,1744061306.835401,1.2015023231506348,2.372089588130453,1744061306.8354023,1.2015023231506348,0.0,1744061306.8354032,1.2015023231506348,-22627416996.071926,1744061306.8354044,1.2015023231506348,0.0,1744061306.835405,1.2015023231506348,28284271247.461903
+1744061306.8547993,1.2215063571929932,0.041613443739632924,1744061306.8548012,1.2215063571929932,-0.0006556382546494058,1744061306.8548036,1.2215063571929932,0.021662622276343926,1744061306.8548055,1.2215063571929932,-56568542383.61545,1744061306.8548064,1.2215063571929932,0.065,1744061306.854808,1.2215063571929932,3.1415926535886327,1744061306.854809,1.2215063571929932,0.06564935303197303,1744061306.8548105,1.2215063571929932,9.453506873793015e-23,1744061306.8548114,1.2215063571929932,2.372089588130453,1744061306.8548126,1.2215063571929932,0.0,1744061306.8548138,1.2215063571929932,-22627416996.071854,1744061306.8548148,1.2215063571929932,0.0,1744061306.8548157,1.2215063571929932,28284271247.461903
+1744061306.8747125,1.241478681564331,0.041613443739632924,1744061306.8747146,1.241478681564331,-0.0006556382546494058,1744061306.8747168,1.241478681564331,0.021662622276343926,1744061306.874719,1.241478681564331,-56568542383.61545,1744061306.87472,1.241478681564331,0.065,1744061306.8747215,1.241478681564331,3.1415926535886327,1744061306.8747225,1.241478681564331,0.06564935303197303,1744061306.8747237,1.241478681564331,9.453506873793015e-23,1744061306.8747246,1.241478681564331,2.372089588130453,1744061306.8747258,1.241478681564331,0.0,1744061306.874727,1.241478681564331,-22627416996.071854,1744061306.8747282,1.241478681564331,0.0,1744061306.8747292,1.241478681564331,28284271247.461903
+1744061306.894868,1.2614798545837402,0.041613443739632924,1744061306.8948705,1.2614798545837402,-0.0006556382546494058,1744061306.8948731,1.2614798545837402,0.021662622276343926,1744061306.8948762,1.2614798545837402,-56568542383.61545,1744061306.894878,1.2614798545837402,0.065,1744061306.8948796,1.2614798545837402,3.1415926535886327,1744061306.8948808,1.2614798545837402,0.06564935303197303,1744061306.894882,1.2614798545837402,9.453506873793015e-23,1744061306.8948834,1.2614798545837402,2.372089588130453,1744061306.8948853,1.2614798545837402,0.0,1744061306.8948865,1.2614798545837402,-22627416996.071854,1744061306.8948877,1.2614798545837402,0.0,1744061306.8948886,1.2614798545837402,28284271247.461903
+1744061306.9148612,1.2814743518829346,0.041613443739632924,1744061306.9148643,1.2814743518829346,-0.0006556382546494058,1744061306.9148667,1.2814743518829346,0.021662622276343926,1744061306.914869,1.2814743518829346,-56568542383.61545,1744061306.9148703,1.2814743518829346,0.065,1744061306.9148715,1.2814743518829346,3.1415926535886327,1744061306.9148731,1.2814743518829346,0.06564935303197303,1744061306.914874,1.2814743518829346,9.453506873793015e-23,1744061306.914875,1.2814743518829346,2.372089588130453,1744061306.9148772,1.2814743518829346,0.0,1744061306.9148781,1.2814743518829346,-22627416996.071854,1744061306.9148793,1.2814743518829346,0.0,1744061306.9148803,1.2814743518829346,28284271247.461903
+1744061306.9348664,1.301450252532959,0.041613443739632924,1744061306.9348683,1.301450252532959,-0.0006556382546494058,1744061306.9348705,1.301450252532959,0.021662622276343926,1744061306.9348726,1.301450252532959,-56568542383.61545,1744061306.9348736,1.301450252532959,0.065,1744061306.9348748,1.301450252532959,3.1415926535886327,1744061306.9348762,1.301450252532959,0.06564935303197303,1744061306.9348772,1.301450252532959,9.453506873793015e-23,1744061306.934878,1.301450252532959,2.372089588130453,1744061306.9348795,1.301450252532959,0.0,1744061306.9348805,1.301450252532959,-22627416996.071854,1744061306.9348812,1.301450252532959,0.0,1744061306.9348824,1.301450252532959,28284271247.461903
+1744061306.9553628,1.3215272426605225,0.041613443739632924,1744061306.9553657,1.3215272426605225,-0.0006556382546494058,1744061306.9553685,1.3215272426605225,0.021662622276343926,1744061306.9553707,1.3215272426605225,-56568542383.61545,1744061306.9553723,1.3215272426605225,0.065,1744061306.9553738,1.3215272426605225,3.1415926535886327,1744061306.9553761,1.3215272426605225,0.06564935303197303,1744061306.955377,1.3215272426605225,9.453506873793015e-23,1744061306.9553785,1.3215272426605225,2.372089588130453,1744061306.9553804,1.3215272426605225,0.0,1744061306.9553814,1.3215272426605225,-22627416996.071854,1744061306.9553828,1.3215272426605225,0.0,1744061306.955384,1.3215272426605225,28284271247.461903
+1744061306.9753006,1.3414552211761475,0.041613443739632924,1744061306.9753027,1.3414552211761475,-0.0006556382546494058,1744061306.9753048,1.3414552211761475,0.021662622276343926,1744061306.9753072,1.3414552211761475,-56568542383.61545,1744061306.9753087,1.3414552211761475,0.065,1744061306.9753098,1.3414552211761475,3.1415926535886327,1744061306.975311,1.3414552211761475,0.06564935303197303,1744061306.9753122,1.3414552211761475,9.453506873793015e-23,1744061306.9753134,1.3414552211761475,2.372089588130453,1744061306.9753149,1.3414552211761475,0.0,1744061306.9753342,1.3414552211761475,-22627416996.071854,1744061306.9753354,1.3414552211761475,0.0,1744061306.9753366,1.3414552211761475,28284271247.461903
+1744061306.9947255,1.3614606857299805,0.041613443739632924,1744061306.9947271,1.3614606857299805,-0.0006556382546494058,1744061306.9947295,1.3614606857299805,0.021662622276343926,1744061306.9947314,1.3614606857299805,-56568542383.61545,1744061306.9947326,1.3614606857299805,0.065,1744061306.9947338,1.3614606857299805,3.1415926535886327,1744061306.994735,1.3614606857299805,0.06564935303197303,1744061306.9947362,1.3614606857299805,9.453506873793015e-23,1744061306.9947371,1.3614606857299805,2.372089588130453,1744061306.9947386,1.3614606857299805,0.0,1744061306.9947398,1.3614606857299805,-22627416996.071854,1744061306.9947407,1.3614606857299805,0.0,1744061306.9947417,1.3614606857299805,28284271247.461903
+1744061307.0146308,1.3814496994018555,0.041613443739632924,1744061307.0146327,1.3814496994018555,-0.0006556382546494058,1744061307.014635,1.3814496994018555,0.021662622276343926,1744061307.014637,1.3814496994018555,-56568542383.61545,1744061307.0146382,1.3814496994018555,0.065,1744061307.0146396,1.3814496994018555,3.1415926535886327,1744061307.0146406,1.3814496994018555,0.06564935303197303,1744061307.0146418,1.3814496994018555,9.453506873793015e-23,1744061307.0146427,1.3814496994018555,2.372089588130453,1744061307.014644,1.3814496994018555,0.0,1744061307.014645,1.3814496994018555,-22627416996.071854,1744061307.014646,1.3814496994018555,0.0,1744061307.014647,1.3814496994018555,28284271247.461903
+1744061307.0349524,1.4014780521392822,0.041613443739632924,1744061307.0349545,1.4014780521392822,-0.0006556382546494058,1744061307.0349565,1.4014780521392822,0.021662622276343926,1744061307.0349588,1.4014780521392822,-56568542383.61545,1744061307.0349598,1.4014780521392822,0.065,1744061307.0349612,1.4014780521392822,3.1415926535886327,1744061307.0349624,1.4014780521392822,0.06564935303197303,1744061307.0349634,1.4014780521392822,9.453506873793015e-23,1744061307.0349646,1.4014780521392822,2.372089588130453,1744061307.034966,1.4014780521392822,0.0,1744061307.034967,1.4014780521392822,-22627416996.071854,1744061307.0349681,1.4014780521392822,0.0,1744061307.034969,1.4014780521392822,28284271247.461903
+1744061307.0550566,1.4215023517608643,0.041613443739632924,1744061307.0550587,1.4215023517608643,-0.0006556382546494058,1744061307.055061,1.4215023517608643,0.021662622276343926,1744061307.055063,1.4215023517608643,-56568542383.61545,1744061307.0550642,1.4215023517608643,0.065,1744061307.0550842,1.4215023517608643,3.1415926535886327,1744061307.0550857,1.4215023517608643,0.06564935303197303,1744061307.0550866,1.4215023517608643,9.453506873793015e-23,1744061307.0550878,1.4215023517608643,2.372089588130453,1744061307.0550895,1.4215023517608643,0.0,1744061307.0550904,1.4215023517608643,-22627416996.071854,1744061307.0550919,1.4215023517608643,0.0,1744061307.055093,1.4215023517608643,28284271247.461903
+1744061307.0747464,1.4414801597595215,0.041613443739632924,1744061307.0747488,1.4414801597595215,-0.0006556382546494058,1744061307.0747507,1.4414801597595215,0.021662622276343926,1744061307.074753,1.4414801597595215,-56568542383.61545,1744061307.0747542,1.4414801597595215,0.065,1744061307.0747557,1.4414801597595215,3.1415926535886327,1744061307.0747566,1.4414801597595215,0.06564935303197303,1744061307.0747578,1.4414801597595215,9.453506873793015e-23,1744061307.074759,1.4414801597595215,2.372089588130453,1744061307.0747604,1.4414801597595215,0.0,1744061307.0747614,1.4414801597595215,-22627416996.071854,1744061307.0747628,1.4414801597595215,0.0,1744061307.0747638,1.4414801597595215,28284271247.461903
+1744061307.0946786,1.4614818096160889,0.041613443739632924,1744061307.0946805,1.4614818096160889,-0.0006556382546494058,1744061307.0946846,1.4614818096160889,0.021662622276343926,1744061307.0946872,1.4614818096160889,-56568542383.61545,1744061307.0946884,1.4614818096160889,0.065,1744061307.0946898,1.4614818096160889,3.1415926535886327,1744061307.0946908,1.4614818096160889,0.06564935303197303,1744061307.0946918,1.4614818096160889,9.453506873793015e-23,1744061307.094693,1.4614818096160889,2.372089588130453,1744061307.0946944,1.4614818096160889,0.0,1744061307.094695,1.4614818096160889,-22627416996.071854,1744061307.0946965,1.4614818096160889,0.0,1744061307.0946972,1.4614818096160889,28284271247.461903
+1744061307.1147146,1.4815025329589844,0.041613443739632924,1744061307.1147165,1.4815025329589844,-0.0006556382546494058,1744061307.1147187,1.4815025329589844,0.021662622276343926,1744061307.1147208,1.4815025329589844,-56568542383.61545,1744061307.1147218,1.4815025329589844,0.065,1744061307.114723,1.4815025329589844,3.1415926535886327,1744061307.1147244,1.4815025329589844,0.06564935303197303,1744061307.114725,1.4815025329589844,9.453506873793015e-23,1744061307.114726,1.4815025329589844,2.372089588130453,1744061307.1147277,1.4815025329589844,0.0,1744061307.1147285,1.4815025329589844,-22627416996.071854,1744061307.1147294,1.4815025329589844,0.0,1744061307.1147306,1.4815025329589844,28284271247.461903
+1744061307.1350021,1.5014910697937012,0.041613443739632924,1744061307.1350038,1.5014910697937012,-0.0006556382546494058,1744061307.135006,1.5014910697937012,0.021662622276343926,1744061307.135008,1.5014910697937012,-56568542383.61545,1744061307.135009,1.5014910697937012,0.065,1744061307.1350102,1.5014910697937012,3.1415926535886327,1744061307.1350114,1.5014910697937012,0.06564935303197303,1744061307.1350121,1.5014910697937012,9.453506873793015e-23,1744061307.135013,1.5014910697937012,2.372089588130453,1744061307.135014,1.5014910697937012,0.0,1744061307.1350152,1.5014910697937012,-22627416996.071854,1744061307.1350162,1.5014910697937012,0.0,1744061307.135017,1.5014910697937012,28284271247.461903
+1744061307.1556716,1.5215117931365967,0.041613443739632924,1744061307.1556756,1.5215117931365967,-0.0006556382546494058,1744061307.155679,1.5215117931365967,0.021662622276343926,1744061307.1556816,1.5215117931365967,-56568542383.61545,1744061307.1556838,1.5215117931365967,0.065,1744061307.155686,1.5215117931365967,3.1415926535886327,1744061307.1556873,1.5215117931365967,0.06564935303197303,1744061307.1556885,1.5215117931365967,9.453506873793015e-23,1744061307.1556895,1.5215117931365967,2.372089588130453,1744061307.1556916,1.5215117931365967,0.0,1744061307.155693,1.5215117931365967,-22627416996.071854,1744061307.1556945,1.5215117931365967,0.0,1744061307.1556957,1.5215117931365967,28284271247.461903
+1744061307.175029,1.541461706161499,0.041613443739632924,1744061307.1750317,1.541461706161499,-0.0006556382546494058,1744061307.1750345,1.541461706161499,0.021662622276343926,1744061307.1750371,1.541461706161499,-56568542383.61545,1744061307.175039,1.541461706161499,0.065,1744061307.1750407,1.541461706161499,3.1415926535886327,1744061307.1750422,1.541461706161499,0.06564935303197303,1744061307.175043,1.541461706161499,9.453506873793015e-23,1744061307.175045,1.541461706161499,2.372089588130453,1744061307.1750655,1.541461706161499,0.0,1744061307.175067,1.541461706161499,-22627416996.071854,1744061307.1750681,1.541461706161499,0.0,1744061307.1750698,1.541461706161499,28284271247.461903
+1744061307.1948493,1.5614988803863525,0.041613443739632924,1744061307.1948512,1.5614988803863525,-0.0006556382546494058,1744061307.194853,1.5614988803863525,0.021662622276343926,1744061307.194855,1.5614988803863525,-56568542383.61545,1744061307.1948562,1.5614988803863525,0.065,1744061307.1948571,1.5614988803863525,3.1415926535886327,1744061307.1948586,1.5614988803863525,0.06564935303197303,1744061307.1948595,1.5614988803863525,9.453506873793015e-23,1744061307.1948602,1.5614988803863525,2.372089588130453,1744061307.1948617,1.5614988803863525,0.0,1744061307.1948626,1.5614988803863525,-22627416996.071854,1744061307.1948636,1.5614988803863525,0.0,1744061307.1948647,1.5614988803863525,28284271247.461903
+1744061307.2147007,1.5814769268035889,0.041613443739632924,1744061307.2147026,1.5814769268035889,-0.0006556382546494058,1744061307.2147048,1.5814769268035889,0.021662622276343926,1744061307.2147064,1.5814769268035889,-56568542383.61545,1744061307.2147074,1.5814769268035889,0.065,1744061307.2147088,1.5814769268035889,3.1415926535886327,1744061307.2147098,1.5814769268035889,0.06564935303197303,1744061307.2147105,1.5814769268035889,9.453506873793015e-23,1744061307.2147117,1.5814769268035889,2.372089588130453,1744061307.2147129,1.5814769268035889,0.0,1744061307.2147138,1.5814769268035889,-22627416996.071854,1744061307.2147152,1.5814769268035889,0.0,1744061307.2147162,1.5814769268035889,28284271247.461903
+1744061307.2361386,1.6015698909759521,0.041613443739632924,1744061307.2361403,1.6015698909759521,-0.0006556382546494058,1744061307.2361424,1.6015698909759521,0.021662622276343926,1744061307.2361443,1.6015698909759521,-56568542383.61545,1744061307.2361457,1.6015698909759521,0.065,1744061307.236147,1.6015698909759521,3.1415926535886327,1744061307.2361479,1.6015698909759521,0.06564935303197303,1744061307.2361488,1.6015698909759521,9.453506873793015e-23,1744061307.2361498,1.6015698909759521,2.372089588130453,1744061307.236151,1.6015698909759521,0.0,1744061307.2361517,1.6015698909759521,-22627416996.071854,1744061307.2361531,1.6015698909759521,0.0,1744061307.2361538,1.6015698909759521,28284271247.461903
+1744061307.255212,1.6215496063232422,0.041613443739632924,1744061307.2552137,1.6215496063232422,-0.0006556382546494058,1744061307.2552161,1.6215496063232422,0.021662622276343926,1744061307.2552185,1.6215496063232422,-56568542383.61545,1744061307.2552197,1.6215496063232422,0.065,1744061307.255221,1.6215496063232422,3.1415926535886327,1744061307.2552223,1.6215496063232422,0.06564935303197303,1744061307.255223,1.6215496063232422,9.453506873793015e-23,1744061307.255224,1.6215496063232422,2.372089588130453,1744061307.255226,1.6215496063232422,0.0,1744061307.2552269,1.6215496063232422,-22627416996.071854,1744061307.255228,1.6215496063232422,0.0,1744061307.2552292,1.6215496063232422,28284271247.461903
+1744061307.2747693,1.6414573192596436,0.041613443739632924,1744061307.2747715,1.6414573192596436,-0.0006556382546494058,1744061307.2747738,1.6414573192596436,0.021662622276343926,1744061307.2747757,1.6414573192596436,-56568542383.61545,1744061307.2747772,1.6414573192596436,0.065,1744061307.2747784,1.6414573192596436,3.1415926535886327,1744061307.2747796,1.6414573192596436,0.06564935303197303,1744061307.2747808,1.6414573192596436,9.453506873793015e-23,1744061307.2747817,1.6414573192596436,2.372089588130453,1744061307.2747831,1.6414573192596436,0.0,1744061307.2747843,1.6414573192596436,-22627416996.071854,1744061307.2747855,1.6414573192596436,0.0,1744061307.2747862,1.6414573192596436,28284271247.461903
+1744061307.2948532,1.6614959239959717,0.041613443739632924,1744061307.294855,1.6614959239959717,-0.0006556382546494058,1744061307.2948573,1.6614959239959717,0.021662622276343926,1744061307.29486,1.6614959239959717,-56568542383.61545,1744061307.294861,1.6614959239959717,0.065,1744061307.2948623,1.6614959239959717,3.1415926535886327,1744061307.2948637,1.6614959239959717,0.06564935303197303,1744061307.2948644,1.6614959239959717,9.453506873793015e-23,1744061307.2948654,1.6614959239959717,2.372089588130453,1744061307.294867,1.6614959239959717,0.0,1744061307.294868,1.6614959239959717,-22627416996.071854,1744061307.294869,1.6614959239959717,0.0,1744061307.2948704,1.6614959239959717,28284271247.461903
+1744061307.31476,1.6814541816711426,0.041613443739632924,1744061307.3147616,1.6814541816711426,-0.0006556382546494058,1744061307.3147638,1.6814541816711426,0.021662622276343926,1744061307.3147655,1.6814541816711426,-56568542383.61545,1744061307.314767,1.6814541816711426,0.065,1744061307.3147678,1.6814541816711426,3.1415926535886327,1744061307.3147688,1.6814541816711426,0.06564935303197303,1744061307.31477,1.6814541816711426,9.453506873793015e-23,1744061307.314771,1.6814541816711426,2.372089588130453,1744061307.3147721,1.6814541816711426,0.0,1744061307.3147733,1.6814541816711426,-22627416996.071854,1744061307.3147743,1.6814541816711426,0.0,1744061307.314775,1.6814541816711426,28284271247.461903
+1744061307.3351586,1.7014567852020264,0.05660641701135045,1744061307.3351603,1.7014567852020264,-0.003039499543521151,1744061307.3351624,1.7014567852020264,0.0218125520090611,1744061307.3351643,1.7014567852020264,-56568542383.6156,1744061307.3351655,1.7014567852020264,0.065,1744061307.3351672,1.7014567852020264,3.1415926535885905,1744061307.3351684,1.7014567852020264,0.06803589356449642,1744061307.3351693,1.7014567852020264,9.797168711823058e-23,1744061307.33517,1.7014567852020264,2.3675650383543414,1744061307.3351712,1.7014567852020264,0.0,1744061307.3351724,1.7014567852020264,-22627416996.076836,1744061307.3351734,1.7014567852020264,0.0,1744061307.3351743,1.7014567852020264,28284271247.461903
+1744061307.3547258,1.7214629650115967,0.05660641701135045,1744061307.3547277,1.7214629650115967,-0.003039499543521151,1744061307.3547297,1.7214629650115967,0.0218125520090611,1744061307.3547318,1.7214629650115967,-56568542383.6156,1744061307.354733,1.7214629650115967,0.065,1744061307.3547342,1.7214629650115967,3.1415926535885905,1744061307.3547354,1.7214629650115967,0.06803589356449642,1744061307.3547363,1.7214629650115967,9.797168711823058e-23,1744061307.3547375,1.7214629650115967,2.3675650383543414,1744061307.3547394,1.7214629650115967,0.0,1744061307.3547404,1.7214629650115967,-22627416996.07547,1744061307.3547418,1.7214629650115967,0.0,1744061307.3547425,1.7214629650115967,28284271247.461903
+1744061307.3748465,1.7415003776550293,0.05660641701135045,1744061307.3748486,1.7415003776550293,-0.003039499543521151,1744061307.3748503,1.7415003776550293,0.0218125520090611,1744061307.3748524,1.7415003776550293,-56568542383.6156,1744061307.3748536,1.7415003776550293,0.065,1744061307.3748548,1.7415003776550293,3.1415926535885905,1744061307.374856,1.7415003776550293,0.06803589356449642,1744061307.374857,1.7415003776550293,9.797168711823058e-23,1744061307.3748581,1.7415003776550293,2.3675650383543414,1744061307.3748596,1.7415003776550293,0.0,1744061307.3748603,1.7415003776550293,-22627416996.07547,1744061307.3748615,1.7415003776550293,0.0,1744061307.3748627,1.7415003776550293,28284271247.461903
+1744061307.3949573,1.7614936828613281,0.05660641701135045,1744061307.3949592,1.7614936828613281,-0.003039499543521151,1744061307.394961,1.7614936828613281,0.0218125520090611,1744061307.3949633,1.7614936828613281,-56568542383.6156,1744061307.3949645,1.7614936828613281,0.065,1744061307.3949656,1.7614936828613281,3.1415926535885905,1744061307.3949668,1.7614936828613281,0.06803589356449642,1744061307.3949678,1.7614936828613281,9.797168711823058e-23,1744061307.394969,1.7614936828613281,2.3675650383543414,1744061307.3949714,1.7614936828613281,0.0,1744061307.3949723,1.7614936828613281,-22627416996.07547,1744061307.394974,1.7614936828613281,0.0,1744061307.3949752,1.7614936828613281,28284271247.461903
+1744061307.4146616,1.781480073928833,0.05660641701135045,1744061307.414663,1.781480073928833,-0.003039499543521151,1744061307.4146652,1.781480073928833,0.0218125520090611,1744061307.4146674,1.781480073928833,-56568542383.6156,1744061307.4146683,1.781480073928833,0.065,1744061307.4146695,1.781480073928833,3.1415926535885905,1744061307.4146707,1.781480073928833,0.06803589356449642,1744061307.4146714,1.781480073928833,9.797168711823058e-23,1744061307.4146724,1.781480073928833,2.3675650383543414,1744061307.4146736,1.781480073928833,0.0,1744061307.4146748,1.781480073928833,-22627416996.07547,1744061307.4146757,1.781480073928833,0.0,1744061307.4146767,1.781480073928833,28284271247.461903
+1744061307.4360065,1.8015034198760986,0.05660641701135045,1744061307.4360085,1.8015034198760986,-0.003039499543521151,1744061307.4360108,1.8015034198760986,0.0218125520090611,1744061307.4360127,1.8015034198760986,-56568542383.6156,1744061307.436014,1.8015034198760986,0.065,1744061307.4360151,1.8015034198760986,3.1415926535885905,1744061307.436016,1.8015034198760986,0.06803589356449642,1744061307.436017,1.8015034198760986,9.797168711823058e-23,1744061307.4360182,1.8015034198760986,2.3675650383543414,1744061307.4360194,1.8015034198760986,0.0,1744061307.4360201,1.8015034198760986,-22627416996.07547,1744061307.4360216,1.8015034198760986,0.0,1744061307.4360223,1.8015034198760986,28284271247.461903
+1744061307.4548664,1.8214621543884277,0.05660641701135045,1744061307.4548683,1.8214621543884277,-0.003039499543521151,1744061307.4548705,1.8214621543884277,0.0218125520090611,1744061307.4548726,1.8214621543884277,-56568542383.6156,1744061307.4548738,1.8214621543884277,0.065,1744061307.4548752,1.8214621543884277,3.1415926535885905,1744061307.4548764,1.8214621543884277,0.06803589356449642,1744061307.4548771,1.8214621543884277,9.797168711823058e-23,1744061307.454878,1.8214621543884277,2.3675650383543414,1744061307.45488,1.8214621543884277,0.0,1744061307.454881,1.8214621543884277,-22627416996.07547,1744061307.4548821,1.8214621543884277,0.0,1744061307.454883,1.8214621543884277,28284271247.461903
+1744061307.474853,1.8414504528045654,0.05660641701135045,1744061307.474855,1.8414504528045654,-0.003039499543521151,1744061307.4748569,1.8414504528045654,0.0218125520090611,1744061307.474859,1.8414504528045654,-56568542383.6156,1744061307.4748602,1.8414504528045654,0.065,1744061307.4748616,1.8414504528045654,3.1415926535885905,1744061307.4748626,1.8414504528045654,0.06803589356449642,1744061307.4748635,1.8414504528045654,9.797168711823058e-23,1744061307.4748647,1.8414504528045654,2.3675650383543414,1744061307.474866,1.8414504528045654,0.0,1744061307.4748669,1.8414504528045654,-22627416996.07547,1744061307.474868,1.8414504528045654,0.0,1744061307.474869,1.8414504528045654,28284271247.461903
+1744061307.4948208,1.8614957332611084,0.05660641701135045,1744061307.494824,1.8614957332611084,-0.003039499543521151,1744061307.4948266,1.8614957332611084,0.0218125520090611,1744061307.4948287,1.8614957332611084,-56568542383.6156,1744061307.4948306,1.8614957332611084,0.065,1744061307.494832,1.8614957332611084,3.1415926535885905,1744061307.4948335,1.8614957332611084,0.06803589356449642,1744061307.4948344,1.8614957332611084,9.797168711823058e-23,1744061307.4948356,1.8614957332611084,2.3675650383543414,1744061307.494837,1.8614957332611084,0.0,1744061307.4948382,1.8614957332611084,-22627416996.07547,1744061307.4948397,1.8614957332611084,0.0,1744061307.4948406,1.8614957332611084,28284271247.461903
+1744061307.51476,1.881479024887085,0.05660641701135045,1744061307.514762,1.881479024887085,-0.003039499543521151,1744061307.5147645,1.881479024887085,0.0218125520090611,1744061307.5147667,1.881479024887085,-56568542383.6156,1744061307.5147676,1.881479024887085,0.065,1744061307.5147688,1.881479024887085,3.1415926535885905,1744061307.51477,1.881479024887085,0.06803589356449642,1744061307.5147707,1.881479024887085,9.797168711823058e-23,1744061307.5147717,1.881479024887085,2.3675650383543414,1744061307.514773,1.881479024887085,0.0,1744061307.5147738,1.881479024887085,-22627416996.07547,1744061307.5147748,1.881479024887085,0.0,1744061307.5147758,1.881479024887085,28284271247.461903
+1744061307.535069,1.9014942646026611,0.05660641701135045,1744061307.535071,1.9014942646026611,-0.003039499543521151,1744061307.535073,1.9014942646026611,0.0218125520090611,1744061307.5350752,1.9014942646026611,-56568542383.6156,1744061307.5350761,1.9014942646026611,0.065,1744061307.5350773,1.9014942646026611,3.1415926535885905,1744061307.5350783,1.9014942646026611,0.06803589356449642,1744061307.5350795,1.9014942646026611,9.797168711823058e-23,1744061307.5350802,1.9014942646026611,2.3675650383543414,1744061307.5350814,1.9014942646026611,0.0,1744061307.5350826,1.9014942646026611,-22627416996.07547,1744061307.5350835,1.9014942646026611,0.0,1744061307.5350845,1.9014942646026611,28284271247.461903
+1744061307.5550148,1.9215214252471924,0.05660641701135045,1744061307.5550172,1.9215214252471924,-0.003039499543521151,1744061307.5550194,1.9215214252471924,0.0218125520090611,1744061307.5550213,1.9215214252471924,-56568542383.6156,1744061307.5550222,1.9215214252471924,0.065,1744061307.5550237,1.9215214252471924,3.1415926535885905,1744061307.5550246,1.9215214252471924,0.06803589356449642,1744061307.5550256,1.9215214252471924,9.797168711823058e-23,1744061307.5550265,1.9215214252471924,2.3675650383543414,1744061307.555028,1.9215214252471924,0.0,1744061307.5550287,1.9215214252471924,-22627416996.07547,1744061307.5550299,1.9215214252471924,0.0,1744061307.5550308,1.9215214252471924,28284271247.461903
+1744061307.5748055,1.941516637802124,0.05660641701135045,1744061307.5748076,1.941516637802124,-0.003039499543521151,1744061307.5748096,1.941516637802124,0.0218125520090611,1744061307.5748117,1.941516637802124,-56568542383.6156,1744061307.5748127,1.941516637802124,0.065,1744061307.5748138,1.941516637802124,3.1415926535885905,1744061307.574815,1.941516637802124,0.06803589356449642,1744061307.5748158,1.941516637802124,9.797168711823058e-23,1744061307.5748167,1.941516637802124,2.3675650383543414,1744061307.5748181,1.941516637802124,0.0,1744061307.574819,1.941516637802124,-22627416996.07547,1744061307.57482,1.941516637802124,0.0,1744061307.5748208,1.941516637802124,28284271247.461903
+1744061307.5949953,1.9614503383636475,0.05660641701135045,1744061307.5949984,1.9614503383636475,-0.003039499543521151,1744061307.5950015,1.9614503383636475,0.0218125520090611,1744061307.5950036,1.9614503383636475,-56568542383.6156,1744061307.595005,1.9614503383636475,0.065,1744061307.5950067,1.9614503383636475,3.1415926535885905,1744061307.5950077,1.9614503383636475,0.06803589356449642,1744061307.5950089,1.9614503383636475,9.797168711823058e-23,1744061307.5950098,1.9614503383636475,2.3675650383543414,1744061307.5950122,1.9614503383636475,0.0,1744061307.5950134,1.9614503383636475,-22627416996.07547,1744061307.595015,1.9614503383636475,0.0,1744061307.5950162,1.9614503383636475,28284271247.461903
+1744061307.6147141,1.9814832210540771,0.05660641701135045,1744061307.6147158,1.9814832210540771,-0.003039499543521151,1744061307.614718,1.9814832210540771,0.0218125520090611,1744061307.6147196,1.9814832210540771,-56568542383.6156,1744061307.614721,1.9814832210540771,0.065,1744061307.6147223,1.9814832210540771,3.1415926535885905,1744061307.614723,1.9814832210540771,0.06803589356449642,1744061307.6147242,1.9814832210540771,9.797168711823058e-23,1744061307.6147249,1.9814832210540771,2.3675650383543414,1744061307.614726,1.9814832210540771,0.0,1744061307.6147273,1.9814832210540771,-22627416996.07547,1744061307.6147282,1.9814832210540771,0.0,1744061307.6147292,1.9814832210540771,28284271247.461903
+1744061307.63525,2.00152850151062,0.05660641701135045,1744061307.635252,2.00152850151062,-0.003039499543521151,1744061307.6352544,2.00152850151062,0.0218125520090611,1744061307.6352563,2.00152850151062,-56568542383.6156,1744061307.6352572,2.00152850151062,0.065,1744061307.6352587,2.00152850151062,3.1415926535885905,1744061307.6352596,2.00152850151062,0.06803589356449642,1744061307.6352606,2.00152850151062,9.797168711823058e-23,1744061307.6352618,2.00152850151062,2.3675650383543414,1744061307.6352627,2.00152850151062,0.0,1744061307.6352637,2.00152850151062,-22627416996.07547,1744061307.6352649,2.00152850151062,0.0,1744061307.6352656,2.00152850151062,28284271247.461903
+1744061307.65493,2.0214967727661133,0.05660641701135045,1744061307.654932,2.0214967727661133,-0.003039499543521151,1744061307.654934,2.0214967727661133,0.0218125520090611,1744061307.654936,2.0214967727661133,-56568542383.6156,1744061307.654937,2.0214967727661133,0.065,1744061307.6549385,2.0214967727661133,3.1415926535885905,1744061307.6549394,2.0214967727661133,0.06803589356449642,1744061307.6549401,2.0214967727661133,9.797168711823058e-23,1744061307.654941,2.0214967727661133,2.3675650383543414,1744061307.654943,2.0214967727661133,0.0,1744061307.6549437,2.0214967727661133,-22627416996.07547,1744061307.6549447,2.0214967727661133,0.0,1744061307.6549459,2.0214967727661133,28284271247.461903
+1744061307.6747775,2.0414650440216064,0.05660641701135045,1744061307.6747794,2.0414650440216064,-0.003039499543521151,1744061307.6747813,2.0414650440216064,0.0218125520090611,1744061307.6747832,2.0414650440216064,-56568542383.6156,1744061307.6747842,2.0414650440216064,0.065,1744061307.6747856,2.0414650440216064,3.1415926535885905,1744061307.6747868,2.0414650440216064,0.06803589356449642,1744061307.6747875,2.0414650440216064,9.797168711823058e-23,1744061307.6747887,2.0414650440216064,2.3675650383543414,1744061307.67479,2.0414650440216064,0.0,1744061307.6747909,2.0414650440216064,-22627416996.07547,1744061307.6747916,2.0414650440216064,0.0,1744061307.6747928,2.0414650440216064,28284271247.461903
+1744061307.6952474,2.061537265777588,0.05660641701135045,1744061307.695249,2.061537265777588,-0.003039499543521151,1744061307.6952512,2.061537265777588,0.0218125520090611,1744061307.695253,2.061537265777588,-56568542383.6156,1744061307.695254,2.061537265777588,0.065,1744061307.6952553,2.061537265777588,3.1415926535885905,1744061307.6952562,2.061537265777588,0.06803589356449642,1744061307.6952574,2.061537265777588,9.797168711823058e-23,1744061307.6952584,2.061537265777588,2.3675650383543414,1744061307.6952598,2.061537265777588,0.0,1744061307.6952608,2.061537265777588,-22627416996.07547,1744061307.695262,2.061537265777588,0.0,1744061307.695263,2.061537265777588,28284271247.461903
+1744061307.7147202,2.081482410430908,0.05660641701135045,1744061307.7147222,2.081482410430908,-0.003039499543521151,1744061307.714724,2.081482410430908,0.0218125520090611,1744061307.7147262,2.081482410430908,-56568542383.6156,1744061307.7147274,2.081482410430908,0.065,1744061307.7147286,2.081482410430908,3.1415926535885905,1744061307.7147298,2.081482410430908,0.06803589356449642,1744061307.7147307,2.081482410430908,9.797168711823058e-23,1744061307.7147315,2.081482410430908,2.3675650383543414,1744061307.7147331,2.081482410430908,0.0,1744061307.7147338,2.081482410430908,-22627416996.07547,1744061307.7147348,2.081482410430908,0.0,1744061307.714736,2.081482410430908,28284271247.461903
+1744061307.734858,2.1014490127563477,0.05660641701135045,1744061307.7348597,2.1014490127563477,-0.003039499543521151,1744061307.7348619,2.1014490127563477,0.0218125520090611,1744061307.7348642,2.1014490127563477,-56568542383.6156,1744061307.7348652,2.1014490127563477,0.065,1744061307.7348664,2.1014490127563477,3.1415926535885905,1744061307.7348676,2.1014490127563477,0.06803589356449642,1744061307.7348683,2.1014490127563477,9.797168711823058e-23,1744061307.734869,2.1014490127563477,2.3675650383543414,1744061307.7348702,2.1014490127563477,0.0,1744061307.7348714,2.1014490127563477,-22627416996.07547,1744061307.734872,2.1014490127563477,0.0,1744061307.734873,2.1014490127563477,28284271247.461903
+1744061307.7553058,2.1214983463287354,0.05660641701135045,1744061307.7553084,2.1214983463287354,-0.003039499543521151,1744061307.7553108,2.1214983463287354,0.0218125520090611,1744061307.755313,2.1214983463287354,-56568542383.6156,1744061307.755314,2.1214983463287354,0.065,1744061307.7553155,2.1214983463287354,3.1415926535885905,1744061307.7553167,2.1214983463287354,0.06803589356449642,1744061307.7553177,2.1214983463287354,9.797168711823058e-23,1744061307.7553189,2.1214983463287354,2.3675650383543414,1744061307.7553203,2.1214983463287354,0.0,1744061307.7553213,2.1214983463287354,-22627416996.07547,1744061307.7553225,2.1214983463287354,0.0,1744061307.7553234,2.1214983463287354,28284271247.461903
+1744061307.774785,2.1414663791656494,0.05660641701135045,1744061307.7747872,2.1414663791656494,-0.003039499543521151,1744061307.774789,2.1414663791656494,0.0218125520090611,1744061307.7747912,2.1414663791656494,-56568542383.6156,1744061307.7747922,2.1414663791656494,0.065,1744061307.7747934,2.1414663791656494,3.1415926535885905,1744061307.7747946,2.1414663791656494,0.06803589356449642,1744061307.7747953,2.1414663791656494,9.797168711823058e-23,1744061307.7747962,2.1414663791656494,2.3675650383543414,1744061307.7747977,2.1414663791656494,0.0,1744061307.7747986,2.1414663791656494,-22627416996.07547,1744061307.7747996,2.1414663791656494,0.0,1744061307.7748005,2.1414663791656494,28284271247.461903
+1744061307.7949064,2.161486864089966,0.05660641701135045,1744061307.7949088,2.161486864089966,-0.003039499543521151,1744061307.7949111,2.161486864089966,0.0218125520090611,1744061307.7949135,2.161486864089966,-56568542383.6156,1744061307.7949147,2.161486864089966,0.065,1744061307.7949166,2.161486864089966,3.1415926535885905,1744061307.7949178,2.161486864089966,0.06803589356449642,1744061307.7949185,2.161486864089966,9.797168711823058e-23,1744061307.79492,2.161486864089966,2.3675650383543414,1744061307.7949214,2.161486864089966,0.0,1744061307.7949226,2.161486864089966,-22627416996.07547,1744061307.7949238,2.161486864089966,0.0,1744061307.7949247,2.161486864089966,28284271247.461903
+1744061307.8149855,2.1814961433410645,0.05660641701135045,1744061307.8149877,2.1814961433410645,-0.003039499543521151,1744061307.8149898,2.1814961433410645,0.0218125520090611,1744061307.814992,2.1814961433410645,-56568542383.6156,1744061307.814993,2.1814961433410645,0.065,1744061307.8149943,2.1814961433410645,3.1415926535885905,1744061307.8149955,2.1814961433410645,0.06803589356449642,1744061307.8149965,2.1814961433410645,9.797168711823058e-23,1744061307.8149972,2.1814961433410645,2.3675650383543414,1744061307.8149989,2.1814961433410645,0.0,1744061307.8149996,2.1814961433410645,-22627416996.07547,1744061307.8150005,2.1814961433410645,0.0,1744061307.8150015,2.1814961433410645,28284271247.461903
+1744061307.8348846,2.201477289199829,0.05465784469071376,1744061307.8348863,2.201477289199829,-0.0024484573400590983,1744061307.8348882,2.201477289199829,0.021793066285854732,1744061307.8348901,2.201477289199829,-56568542383.61558,1744061307.8348913,2.201477289199829,0.065,1744061307.8348927,2.201477289199829,3.1415926535886007,1744061307.834894,2.201477289199829,0.06745809954083476,1744061307.8348947,2.201477289199829,9.713966372089195e-23,1744061307.8348956,2.201477289199829,2.3686596632657775,1744061307.8348966,2.201477289199829,0.0,1744061307.8348978,2.201477289199829,-22627416996.07427,1744061307.8348987,2.201477289199829,0.0,1744061307.8348997,2.201477289199829,28284271247.461903
+1744061307.8549438,2.22149658203125,0.05465784469071376,1744061307.8549461,2.22149658203125,-0.0024484573400590983,1744061307.8549676,2.22149658203125,0.021793066285854732,1744061307.8549702,2.22149658203125,-56568542383.61558,1744061307.8549716,2.22149658203125,0.065,1744061307.854973,2.22149658203125,3.1415926535886007,1744061307.8549745,2.22149658203125,0.06745809954083476,1744061307.8549757,2.22149658203125,9.713966372089195e-23,1744061307.8549767,2.22149658203125,2.3686596632657775,1744061307.8549786,2.22149658203125,0.0,1744061307.8549795,2.22149658203125,-22627416996.074596,1744061307.8549814,2.22149658203125,0.0,1744061307.855003,2.22149658203125,28284271247.461903
+1744061307.8746881,2.2414543628692627,0.05465784469071376,1744061307.87469,2.2414543628692627,-0.0024484573400590983,1744061307.8746922,2.2414543628692627,0.021793066285854732,1744061307.874694,2.2414543628692627,-56568542383.61558,1744061307.874695,2.2414543628692627,0.065,1744061307.8746965,2.2414543628692627,3.1415926535886007,1744061307.8746974,2.2414543628692627,0.06745809954083476,1744061307.8746984,2.2414543628692627,9.713966372089195e-23,1744061307.8746994,2.2414543628692627,2.3686596632657775,1744061307.8747008,2.2414543628692627,0.0,1744061307.8747015,2.2414543628692627,-22627416996.074596,1744061307.874703,2.2414543628692627,0.0,1744061307.874704,2.2414543628692627,28284271247.461903
+1744061307.8955474,2.2614901065826416,0.05465784469071376,1744061307.8955495,2.2614901065826416,-0.0024484573400590983,1744061307.8955517,2.2614901065826416,0.021793066285854732,1744061307.8955538,2.2614901065826416,-56568542383.61558,1744061307.8955548,2.2614901065826416,0.065,1744061307.8955562,2.2614901065826416,3.1415926535886007,1744061307.8955574,2.2614901065826416,0.06745809954083476,1744061307.895558,2.2614901065826416,9.713966372089195e-23,1744061307.895559,2.2614901065826416,2.3686596632657775,1744061307.8955607,2.2614901065826416,0.0,1744061307.8955617,2.2614901065826416,-22627416996.074596,1744061307.8955626,2.2614901065826416,0.0,1744061307.8955636,2.2614901065826416,28284271247.461903
+1744061307.9147174,2.28144907951355,0.05465784469071376,1744061307.9147193,2.28144907951355,-0.0024484573400590983,1744061307.9147213,2.28144907951355,0.021793066285854732,1744061307.9147234,2.28144907951355,-56568542383.61558,1744061307.9147243,2.28144907951355,0.065,1744061307.9147255,2.28144907951355,3.1415926535886007,1744061307.9147267,2.28144907951355,0.06745809954083476,1744061307.9147277,2.28144907951355,9.713966372089195e-23,1744061307.9147286,2.28144907951355,2.3686596632657775,1744061307.9147298,2.28144907951355,0.0,1744061307.9147308,2.28144907951355,-22627416996.074596,1744061307.9147317,2.28144907951355,0.0,1744061307.9147327,2.28144907951355,28284271247.461903
+1744061307.9362392,2.3014988899230957,0.05465784469071376,1744061307.936267,2.3014988899230957,-0.0024484573400590983,1744061307.9362698,2.3014988899230957,0.021793066285854732,1744061307.9362721,2.3014988899230957,-56568542383.61558,1744061307.9362733,2.3014988899230957,0.065,1744061307.9362931,2.3014988899230957,3.1415926535886007,1744061307.9362943,2.3014988899230957,0.06745809954083476,1744061307.9362955,2.3014988899230957,9.713966372089195e-23,1744061307.9362967,2.3014988899230957,2.3686596632657775,1744061307.936298,2.3014988899230957,0.0,1744061307.9362993,2.3014988899230957,-22627416996.074596,1744061307.9363008,2.3014988899230957,0.0,1744061307.9363017,2.3014988899230957,28284271247.461903
+1744061307.9558547,2.321497678756714,0.05465784469071376,1744061307.955857,2.321497678756714,-0.0024484573400590983,1744061307.95586,2.321497678756714,0.021793066285854732,1744061307.9558623,2.321497678756714,-56568542383.61558,1744061307.9558632,2.321497678756714,0.065,1744061307.955865,2.321497678756714,3.1415926535886007,1744061307.9558659,2.321497678756714,0.06745809954083476,1744061307.9558666,2.321497678756714,9.713966372089195e-23,1744061307.955868,2.321497678756714,2.3686596632657775,1744061307.9558694,2.321497678756714,0.0,1744061307.9558704,2.321497678756714,-22627416996.074596,1744061307.9558716,2.321497678756714,0.0,1744061307.9558725,2.321497678756714,28284271247.461903
+1744061307.9748256,2.3414785861968994,0.05465784469071376,1744061307.9748278,2.3414785861968994,-0.0024484573400590983,1744061307.97483,2.3414785861968994,0.021793066285854732,1744061307.9748318,2.3414785861968994,-56568542383.61558,1744061307.9748333,2.3414785861968994,0.065,1744061307.9748344,2.3414785861968994,3.1415926535886007,1744061307.9748354,2.3414785861968994,0.06745809954083476,1744061307.974836,2.3414785861968994,9.713966372089195e-23,1744061307.9748373,2.3414785861968994,2.3686596632657775,1744061307.9748385,2.3414785861968994,0.0,1744061307.9748392,2.3414785861968994,-22627416996.074596,1744061307.9748406,2.3414785861968994,0.0,1744061307.9748416,2.3414785861968994,28284271247.461903
+1744061307.994716,2.3614823818206787,0.05465784469071376,1744061307.9947176,2.3614823818206787,-0.0024484573400590983,1744061307.9947197,2.3614823818206787,0.021793066285854732,1744061307.994722,2.3614823818206787,-56568542383.61558,1744061307.994723,2.3614823818206787,0.065,1744061307.9947243,2.3614823818206787,3.1415926535886007,1744061307.9947255,2.3614823818206787,0.06745809954083476,1744061307.9947264,2.3614823818206787,9.713966372089195e-23,1744061307.9947271,2.3614823818206787,2.3686596632657775,1744061307.9947288,2.3614823818206787,0.0,1744061307.9947298,2.3614823818206787,-22627416996.074596,1744061307.9947307,2.3614823818206787,0.0,1744061307.9947317,2.3614823818206787,28284271247.461903
+1744061308.014711,2.381446361541748,0.05465784469071376,1744061308.0147128,2.381446361541748,-0.0024484573400590983,1744061308.0147147,2.381446361541748,0.021793066285854732,1744061308.0147166,2.381446361541748,-56568542383.61558,1744061308.0147176,2.381446361541748,0.065,1744061308.014719,2.381446361541748,3.1415926535886007,1744061308.0147202,2.381446361541748,0.06745809954083476,1744061308.014721,2.381446361541748,9.713966372089195e-23,1744061308.014722,2.381446361541748,2.3686596632657775,1744061308.0147233,2.381446361541748,0.0,1744061308.0147243,2.381446361541748,-22627416996.074596,1744061308.0147254,2.381446361541748,0.0,1744061308.0147264,2.381446361541748,28284271247.461903
+1744061308.0349982,2.4014506340026855,0.05465784469071376,1744061308.0349998,2.4014506340026855,-0.0024484573400590983,1744061308.0350018,2.4014506340026855,0.021793066285854732,1744061308.0350037,2.4014506340026855,-56568542383.61558,1744061308.0350046,2.4014506340026855,0.065,1744061308.035006,2.4014506340026855,3.1415926535886007,1744061308.035007,2.4014506340026855,0.06745809954083476,1744061308.035008,2.4014506340026855,9.713966372089195e-23,1744061308.035009,2.4014506340026855,2.3686596632657775,1744061308.0350103,2.4014506340026855,0.0,1744061308.0350113,2.4014506340026855,-22627416996.074596,1744061308.035012,2.4014506340026855,0.0,1744061308.0350132,2.4014506340026855,28284271247.461903
+1744061308.0551348,2.4215216636657715,0.05465784469071376,1744061308.0551379,2.4215216636657715,-0.0024484573400590983,1744061308.0551414,2.4215216636657715,0.021793066285854732,1744061308.0551436,2.4215216636657715,-56568542383.61558,1744061308.0551448,2.4215216636657715,0.065,1744061308.0551462,2.4215216636657715,3.1415926535886007,1744061308.0551472,2.4215216636657715,0.06745809954083476,1744061308.0551481,2.4215216636657715,9.713966372089195e-23,1744061308.055149,2.4215216636657715,2.3686596632657775,1744061308.0551505,2.4215216636657715,0.0,1744061308.0551517,2.4215216636657715,-22627416996.074596,1744061308.0551527,2.4215216636657715,0.0,1744061308.0551536,2.4215216636657715,28284271247.461903
+1744061308.0747752,2.4414825439453125,0.05465784469071376,1744061308.0747771,2.4414825439453125,-0.0024484573400590983,1744061308.074779,2.4414825439453125,0.021793066285854732,1744061308.0747812,2.4414825439453125,-56568542383.61558,1744061308.0747824,2.4414825439453125,0.065,1744061308.074784,2.4414825439453125,3.1415926535886007,1744061308.074785,2.4414825439453125,0.06745809954083476,1744061308.0747857,2.4414825439453125,9.713966372089195e-23,1744061308.074787,2.4414825439453125,2.3686596632657775,1744061308.0747886,2.4414825439453125,0.0,1744061308.0747895,2.4414825439453125,-22627416996.074596,1744061308.0747907,2.4414825439453125,0.0,1744061308.0747914,2.4414825439453125,28284271247.461903
+1744061308.0948105,2.46146559715271,0.05465784469071376,1744061308.0948122,2.46146559715271,-0.0024484573400590983,1744061308.0948145,2.46146559715271,0.021793066285854732,1744061308.0948167,2.46146559715271,-56568542383.61558,1744061308.0948179,2.46146559715271,0.065,1744061308.0948188,2.46146559715271,3.1415926535886007,1744061308.09482,2.46146559715271,0.06745809954083476,1744061308.094821,2.46146559715271,9.713966372089195e-23,1744061308.094822,2.46146559715271,2.3686596632657775,1744061308.0948234,2.46146559715271,0.0,1744061308.0948246,2.46146559715271,-22627416996.074596,1744061308.0948265,2.46146559715271,0.0,1744061308.0948281,2.46146559715271,28284271247.461903
+1744061308.1148548,2.4814629554748535,0.05465784469071376,1744061308.1148565,2.4814629554748535,-0.0024484573400590983,1744061308.1148584,2.4814629554748535,0.021793066285854732,1744061308.1148605,2.4814629554748535,-56568542383.61558,1744061308.1148617,2.4814629554748535,0.065,1744061308.114863,2.4814629554748535,3.1415926535886007,1744061308.1148639,2.4814629554748535,0.06745809954083476,1744061308.1148648,2.4814629554748535,9.713966372089195e-23,1744061308.114866,2.4814629554748535,2.3686596632657775,1744061308.1148674,2.4814629554748535,0.0,1744061308.1148684,2.4814629554748535,-22627416996.074596,1744061308.1148696,2.4814629554748535,0.0,1744061308.1148705,2.4814629554748535,28284271247.461903
+1744061308.1357603,2.501499652862549,0.05465784469071376,1744061308.1357625,2.501499652862549,-0.0024484573400590983,1744061308.135783,2.501499652862549,0.021793066285854732,1744061308.135785,2.501499652862549,-56568542383.61558,1744061308.1357863,2.501499652862549,0.065,1744061308.1357875,2.501499652862549,3.1415926535886007,1744061308.135789,2.501499652862549,0.06745809954083476,1744061308.1357896,2.501499652862549,9.713966372089195e-23,1744061308.1357906,2.501499652862549,2.3686596632657775,1744061308.1357918,2.501499652862549,0.0,1744061308.135793,2.501499652862549,-22627416996.074596,1744061308.135794,2.501499652862549,0.0,1744061308.1357949,2.501499652862549,28284271247.461903
+1744061308.154808,2.521472454071045,0.05465784469071376,1744061308.15481,2.521472454071045,-0.0024484573400590983,1744061308.154812,2.521472454071045,0.021793066285854732,1744061308.1548142,2.521472454071045,-56568542383.61558,1744061308.1548154,2.521472454071045,0.065,1744061308.1548166,2.521472454071045,3.1415926535886007,1744061308.1548176,2.521472454071045,0.06745809954083476,1744061308.1548183,2.521472454071045,9.713966372089195e-23,1744061308.1548193,2.521472454071045,2.3686596632657775,1744061308.1548207,2.521472454071045,0.0,1744061308.1548216,2.521472454071045,-22627416996.074596,1744061308.154823,2.521472454071045,0.0,1744061308.154824,2.521472454071045,28284271247.461903
+1744061308.174812,2.541499614715576,0.05465784469071376,1744061308.174814,2.541499614715576,-0.0024484573400590983,1744061308.1748164,2.541499614715576,0.021793066285854732,1744061308.1748183,2.541499614715576,-56568542383.61558,1744061308.1748192,2.541499614715576,0.065,1744061308.1748207,2.541499614715576,3.1415926535886007,1744061308.1748216,2.541499614715576,0.06745809954083476,1744061308.1748223,2.541499614715576,9.713966372089195e-23,1744061308.1748235,2.541499614715576,2.3686596632657775,1744061308.1748247,2.541499614715576,0.0,1744061308.1748257,2.541499614715576,-22627416996.074596,1744061308.1748269,2.541499614715576,0.0,1744061308.1748278,2.541499614715576,28284271247.461903
+1744061308.1954,2.561492919921875,0.05465784469071376,1744061308.195403,2.561492919921875,-0.0024484573400590983,1744061308.1954055,2.561492919921875,0.021793066285854732,1744061308.1954086,2.561492919921875,-56568542383.61558,1744061308.19541,2.561492919921875,0.065,1744061308.1954117,2.561492919921875,3.1415926535886007,1744061308.1954129,2.561492919921875,0.06745809954083476,1744061308.195414,2.561492919921875,9.713966372089195e-23,1744061308.1954153,2.561492919921875,2.3686596632657775,1744061308.1954174,2.561492919921875,0.0,1744061308.1954186,2.561492919921875,-22627416996.074596,1744061308.1954195,2.561492919921875,0.0,1744061308.195421,2.561492919921875,28284271247.461903
+1744061308.2147784,2.581479549407959,0.05465784469071376,1744061308.21478,2.581479549407959,-0.0024484573400590983,1744061308.2147822,2.581479549407959,0.021793066285854732,1744061308.214784,2.581479549407959,-56568542383.61558,1744061308.2147853,2.581479549407959,0.065,1744061308.2147863,2.581479549407959,3.1415926535886007,1744061308.2147872,2.581479549407959,0.06745809954083476,1744061308.2147882,2.581479549407959,9.713966372089195e-23,1744061308.2147892,2.581479549407959,2.3686596632657775,1744061308.2147906,2.581479549407959,0.0,1744061308.2147918,2.581479549407959,-22627416996.074596,1744061308.2147927,2.581479549407959,0.0,1744061308.2147934,2.581479549407959,28284271247.461903
+1744061308.235127,2.601487874984741,0.05465784469071376,1744061308.2351289,2.601487874984741,-0.0024484573400590983,1744061308.2351305,2.601487874984741,0.021793066285854732,1744061308.2351327,2.601487874984741,-56568542383.61558,1744061308.2351336,2.601487874984741,0.065,1744061308.2351346,2.601487874984741,3.1415926535886007,1744061308.2351358,2.601487874984741,0.06745809954083476,1744061308.2351367,2.601487874984741,9.713966372089195e-23,1744061308.2351375,2.601487874984741,2.3686596632657775,1744061308.235139,2.601487874984741,0.0,1744061308.2351396,2.601487874984741,-22627416996.074596,1744061308.2351406,2.601487874984741,0.0,1744061308.2351413,2.601487874984741,28284271247.461903
+1744061308.2549345,2.6214513778686523,0.05465784469071376,1744061308.2549374,2.6214513778686523,-0.0024484573400590983,1744061308.2549396,2.6214513778686523,0.021793066285854732,1744061308.2549427,2.6214513778686523,-56568542383.61558,1744061308.2549443,2.6214513778686523,0.065,1744061308.254946,2.6214513778686523,3.1415926535886007,1744061308.2549477,2.6214513778686523,0.06745809954083476,1744061308.2549486,2.6214513778686523,9.713966372089195e-23,1744061308.2549498,2.6214513778686523,2.3686596632657775,1744061308.2549562,2.6214513778686523,0.0,1744061308.2549572,2.6214513778686523,-22627416996.074596,1744061308.2549586,2.6214513778686523,0.0,1744061308.2549605,2.6214513778686523,28284271247.461903
+1744061308.274725,2.6414942741394043,0.05465784469071376,1744061308.2747266,2.6414942741394043,-0.0024484573400590983,1744061308.2747288,2.6414942741394043,0.021793066285854732,1744061308.2747307,2.6414942741394043,-56568542383.61558,1744061308.2747319,2.6414942741394043,0.065,1744061308.274733,2.6414942741394043,3.1415926535886007,1744061308.2747343,2.6414942741394043,0.06745809954083476,1744061308.2747352,2.6414942741394043,9.713966372089195e-23,1744061308.2747362,2.6414942741394043,2.3686596632657775,1744061308.2747374,2.6414942741394043,0.0,1744061308.2747386,2.6414942741394043,-22627416996.074596,1744061308.2747395,2.6414942741394043,0.0,1744061308.2747402,2.6414942741394043,28284271247.461903
+1744061308.294716,2.6614527702331543,0.05465784469071376,1744061308.294718,2.6614527702331543,-0.0024484573400590983,1744061308.2947202,2.6614527702331543,0.021793066285854732,1744061308.2947223,2.6614527702331543,-56568542383.61558,1744061308.2947233,2.6614527702331543,0.065,1744061308.294725,2.6614527702331543,3.1415926535886007,1744061308.294726,2.6614527702331543,0.06745809954083476,1744061308.2947266,2.6614527702331543,9.713966372089195e-23,1744061308.2947276,2.6614527702331543,2.3686596632657775,1744061308.294729,2.6614527702331543,0.0,1744061308.29473,2.6614527702331543,-22627416996.074596,1744061308.294731,2.6614527702331543,0.0,1744061308.2947319,2.6614527702331543,28284271247.461903
+1744061308.3148165,2.681518316268921,0.05465784469071376,1744061308.3148184,2.681518316268921,-0.0024484573400590983,1744061308.3148203,2.681518316268921,0.021793066285854732,1744061308.3148224,2.681518316268921,-56568542383.61558,1744061308.3148234,2.681518316268921,0.065,1744061308.3148248,2.681518316268921,3.1415926535886007,1744061308.314826,2.681518316268921,0.06745809954083476,1744061308.3148267,2.681518316268921,9.713966372089195e-23,1744061308.314828,2.681518316268921,2.3686596632657775,1744061308.3148293,2.681518316268921,0.0,1744061308.3148303,2.681518316268921,-22627416996.074596,1744061308.3148313,2.681518316268921,0.0,1744061308.3148324,2.681518316268921,28284271247.461903
+1744061308.3352988,2.701463460922241,0.06277094660244345,1744061308.335303,2.701463460922241,-0.009242870528550958,1744061308.335311,2.701463460922241,0.021874197304972032,1744061308.3353143,2.701463460922241,-56568542383.61566,1744061308.335317,2.701463460922241,0.065,1744061308.3353205,2.701463460922241,3.141592653588481,1744061308.335323,2.701463460922241,0.07424089894901968,1744061308.3353255,2.701463460922241,1.0690689490706572e-22,1744061308.3353274,2.701463460922241,2.355841557084658,1744061308.335329,2.701463460922241,0.0,1744061308.3353305,2.701463460922241,-22627416996.088696,1744061308.3353324,2.701463460922241,0.0,1744061308.3353338,2.701463460922241,28284271247.461903
+1744061308.3552783,2.7214884757995605,0.06277094660244345,1744061308.3552804,2.7214884757995605,-0.009242870528550958,1744061308.3552828,2.7214884757995605,0.021874197304972032,1744061308.3552847,2.7214884757995605,-56568542383.61566,1744061308.3552856,2.7214884757995605,0.065,1744061308.3552868,2.7214884757995605,3.141592653588481,1744061308.355288,2.7214884757995605,0.07424089894901968,1744061308.3552887,2.7214884757995605,1.0690689490706572e-22,1744061308.35529,2.7214884757995605,2.355841557084658,1744061308.3552911,2.7214884757995605,0.0,1744061308.355292,2.7214884757995605,-22627416996.08485,1744061308.3552933,2.7214884757995605,0.0,1744061308.3552942,2.7214884757995605,28284271247.461903
+1744061308.375284,2.741532802581787,0.06277094660244345,1744061308.375286,2.741532802581787,-0.009242870528550958,1744061308.3752882,2.741532802581787,0.021874197304972032,1744061308.3752904,2.741532802581787,-56568542383.61566,1744061308.3752913,2.741532802581787,0.065,1744061308.375293,2.741532802581787,3.141592653588481,1744061308.375294,2.741532802581787,0.07424089894901968,1744061308.3752947,2.741532802581787,1.0690689490706572e-22,1744061308.3752956,2.741532802581787,2.355841557084658,1744061308.3753152,2.741532802581787,0.0,1744061308.3753161,2.741532802581787,-22627416996.08485,1744061308.3753176,2.741532802581787,0.0,1744061308.3753185,2.741532802581787,28284271247.461903
+1744061308.3946817,2.7614505290985107,0.06277094660244345,1744061308.3946834,2.7614505290985107,-0.009242870528550958,1744061308.3946857,2.7614505290985107,0.021874197304972032,1744061308.3946877,2.7614505290985107,-56568542383.61566,1744061308.394689,2.7614505290985107,0.065,1744061308.39469,2.7614505290985107,3.141592653588481,1744061308.394691,2.7614505290985107,0.07424089894901968,1744061308.3946922,2.7614505290985107,1.0690689490706572e-22,1744061308.3946931,2.7614505290985107,2.355841557084658,1744061308.3946943,2.7614505290985107,0.0,1744061308.3946955,2.7614505290985107,-22627416996.08485,1744061308.3946965,2.7614505290985107,0.0,1744061308.3946974,2.7614505290985107,28284271247.461903
+1744061308.415022,2.781480312347412,0.06277094660244345,1744061308.4150236,2.781480312347412,-0.009242870528550958,1744061308.4150257,2.781480312347412,0.021874197304972032,1744061308.4150279,2.781480312347412,-56568542383.61566,1744061308.415029,2.781480312347412,0.065,1744061308.4150302,2.781480312347412,3.141592653588481,1744061308.4150314,2.781480312347412,0.07424089894901968,1744061308.4150324,2.781480312347412,1.0690689490706572e-22,1744061308.4150333,2.781480312347412,2.355841557084658,1744061308.4150512,2.781480312347412,0.0,1744061308.415052,2.781480312347412,-22627416996.08485,1744061308.4150531,2.781480312347412,0.0,1744061308.415054,2.781480312347412,28284271247.461903
+1744061308.435079,2.8014719486236572,0.06277094660244345,1744061308.4350808,2.8014719486236572,-0.009242870528550958,1744061308.4350827,2.8014719486236572,0.021874197304972032,1744061308.435085,2.8014719486236572,-56568542383.61566,1744061308.435086,2.8014719486236572,0.065,1744061308.4350872,2.8014719486236572,3.141592653588481,1744061308.4350882,2.8014719486236572,0.07424089894901968,1744061308.4350889,2.8014719486236572,1.0690689490706572e-22,1744061308.4350898,2.8014719486236572,2.355841557084658,1744061308.4350915,2.8014719486236572,0.0,1744061308.4350922,2.8014719486236572,-22627416996.08485,1744061308.4350932,2.8014719486236572,0.0,1744061308.4350944,2.8014719486236572,28284271247.461903
+1744061308.4554179,2.8214874267578125,0.06277094660244345,1744061308.455422,2.8214874267578125,-0.009242870528550958,1744061308.4554443,2.8214874267578125,0.021874197304972032,1744061308.4554484,2.8214874267578125,-56568542383.61566,1744061308.4554508,2.8214874267578125,0.065,1744061308.4554539,2.8214874267578125,3.141592653588481,1744061308.4554737,2.8214874267578125,0.07424089894901968,1744061308.4554758,2.8214874267578125,1.0690689490706572e-22,1744061308.4554777,2.8214874267578125,2.355841557084658,1744061308.4554818,2.8214874267578125,0.0,1744061308.4554844,2.8214874267578125,-22627416996.08485,1744061308.455487,2.8214874267578125,0.0,1744061308.4554894,2.8214874267578125,28284271247.461903
+1744061308.4746747,2.841482639312744,0.06277094660244345,1744061308.4746764,2.841482639312744,-0.009242870528550958,1744061308.4746785,2.841482639312744,0.021874197304972032,1744061308.474681,2.841482639312744,-56568542383.61566,1744061308.4746819,2.841482639312744,0.065,1744061308.474683,2.841482639312744,3.141592653588481,1744061308.4746842,2.841482639312744,0.07424089894901968,1744061308.474685,2.841482639312744,1.0690689490706572e-22,1744061308.474686,2.841482639312744,2.355841557084658,1744061308.4746873,2.841482639312744,0.0,1744061308.4746883,2.841482639312744,-22627416996.08485,1744061308.4746892,2.841482639312744,0.0,1744061308.4746902,2.841482639312744,28284271247.461903
+1744061308.4948344,2.8614583015441895,0.06277094660244345,1744061308.4948366,2.8614583015441895,-0.009242870528550958,1744061308.4948385,2.8614583015441895,0.021874197304972032,1744061308.4948406,2.8614583015441895,-56568542383.61566,1744061308.4948416,2.8614583015441895,0.065,1744061308.4948428,2.8614583015441895,3.141592653588481,1744061308.494844,2.8614583015441895,0.07424089894901968,1744061308.494845,2.8614583015441895,1.0690689490706572e-22,1744061308.4948456,2.8614583015441895,2.355841557084658,1744061308.4948473,2.8614583015441895,0.0,1744061308.494848,2.8614583015441895,-22627416996.08485,1744061308.4948492,2.8614583015441895,0.0,1744061308.4948504,2.8614583015441895,28284271247.461903
+1744061308.514826,2.881488084793091,0.06277094660244345,1744061308.5148277,2.881488084793091,-0.009242870528550958,1744061308.51483,2.881488084793091,0.021874197304972032,1744061308.514832,2.881488084793091,-56568542383.61566,1744061308.5148332,2.881488084793091,0.065,1744061308.5148344,2.881488084793091,3.141592653588481,1744061308.5148354,2.881488084793091,0.07424089894901968,1744061308.5148365,2.881488084793091,1.0690689490706572e-22,1744061308.5148373,2.881488084793091,2.355841557084658,1744061308.5148387,2.881488084793091,0.0,1744061308.51484,2.881488084793091,-22627416996.08485,1744061308.5148408,2.881488084793091,0.0,1744061308.5148418,2.881488084793091,28284271247.461903
+1744061308.534907,2.90144944190979,0.06277094660244345,1744061308.5349088,2.90144944190979,-0.009242870528550958,1744061308.5349107,2.90144944190979,0.021874197304972032,1744061308.5349128,2.90144944190979,-56568542383.61566,1744061308.5349138,2.90144944190979,0.065,1744061308.5349147,2.90144944190979,3.141592653588481,1744061308.534916,2.90144944190979,0.07424089894901968,1744061308.5349169,2.90144944190979,1.0690689490706572e-22,1744061308.5349176,2.90144944190979,2.355841557084658,1744061308.534919,2.90144944190979,0.0,1744061308.53492,2.90144944190979,-22627416996.08485,1744061308.534921,2.90144944190979,0.0,1744061308.5349216,2.90144944190979,28284271247.461903
+1744061308.5549133,2.9214720726013184,0.06277094660244345,1744061308.5549157,2.9214720726013184,-0.009242870528550958,1744061308.554918,2.9214720726013184,0.021874197304972032,1744061308.5549202,2.9214720726013184,-56568542383.61566,1744061308.5549214,2.9214720726013184,0.065,1744061308.5549228,2.9214720726013184,3.141592653588481,1744061308.5549238,2.9214720726013184,0.07424089894901968,1744061308.5549247,2.9214720726013184,1.0690689490706572e-22,1744061308.554926,2.9214720726013184,2.355841557084658,1744061308.5549276,2.9214720726013184,0.0,1744061308.5549283,2.9214720726013184,-22627416996.08485,1744061308.5549297,2.9214720726013184,0.0,1744061308.5549304,2.9214720726013184,28284271247.461903
+1744061308.5746913,2.9414725303649902,0.06277094660244345,1744061308.5746932,2.9414725303649902,-0.009242870528550958,1744061308.574695,2.9414725303649902,0.021874197304972032,1744061308.5746975,2.9414725303649902,-56568542383.61566,1744061308.5746984,2.9414725303649902,0.065,1744061308.5746999,2.9414725303649902,3.141592653588481,1744061308.5747008,2.9414725303649902,0.07424089894901968,1744061308.5747018,2.9414725303649902,1.0690689490706572e-22,1744061308.5747025,2.9414725303649902,2.355841557084658,1744061308.5747042,2.9414725303649902,0.0,1744061308.574705,2.9414725303649902,-22627416996.08485,1744061308.5747058,2.9414725303649902,0.0,1744061308.574707,2.9414725303649902,28284271247.461903
+1744061308.5947325,2.961474657058716,0.06277094660244345,1744061308.594735,2.961474657058716,-0.009242870528550958,1744061308.5947368,2.961474657058716,0.021874197304972032,1744061308.594739,2.961474657058716,-56568542383.61566,1744061308.5947402,2.961474657058716,0.065,1744061308.5947416,2.961474657058716,3.141592653588481,1744061308.5947425,2.961474657058716,0.07424089894901968,1744061308.5947433,2.961474657058716,1.0690689490706572e-22,1744061308.5947447,2.961474657058716,2.355841557084658,1744061308.5947459,2.961474657058716,0.0,1744061308.5947468,2.961474657058716,-22627416996.08485,1744061308.594748,2.961474657058716,0.0,1744061308.594749,2.961474657058716,28284271247.461903
+1744061308.614842,2.9815354347229004,0.06277094660244345,1744061308.6148438,2.9815354347229004,-0.009242870528550958,1744061308.614846,2.9815354347229004,0.021874197304972032,1744061308.614848,2.9815354347229004,-56568542383.61566,1744061308.614849,2.9815354347229004,0.065,1744061308.6148503,2.9815354347229004,3.141592653588481,1744061308.6148512,2.9815354347229004,0.07424089894901968,1744061308.6148522,2.9815354347229004,1.0690689490706572e-22,1744061308.6148531,2.9815354347229004,2.355841557084658,1744061308.6148543,2.9815354347229004,0.0,1744061308.6148555,2.9815354347229004,-22627416996.08485,1744061308.6148565,2.9815354347229004,0.0,1744061308.6148574,2.9815354347229004,28284271247.461903
+1744061308.6349545,3.0015087127685547,0.06277094660244345,1744061308.6349561,3.0015087127685547,-0.009242870528550958,1744061308.6349583,3.0015087127685547,0.021874197304972032,1744061308.6349604,3.0015087127685547,-56568542383.61566,1744061308.6349614,3.0015087127685547,0.065,1744061308.6349635,3.0015087127685547,3.141592653588481,1744061308.6349654,3.0015087127685547,0.07424089894901968,1744061308.634967,3.0015087127685547,1.0690689490706572e-22,1744061308.6349685,3.0015087127685547,2.355841557084658,1744061308.6349707,3.0015087127685547,0.0,1744061308.634972,3.0015087127685547,-22627416996.08485,1744061308.6349738,3.0015087127685547,0.0,1744061308.6349747,3.0015087127685547,28284271247.461903
+1744061308.65507,3.0214710235595703,0.06277094660244345,1744061308.6550736,3.0214710235595703,-0.009242870528550958,1744061308.6550775,3.0214710235595703,0.021874197304972032,1744061308.6550794,3.0214710235595703,-56568542383.61566,1744061308.6550815,3.0214710235595703,0.065,1744061308.6550832,3.0214710235595703,3.141592653588481,1744061308.655085,3.0214710235595703,0.07424089894901968,1744061308.6550863,3.0214710235595703,1.0690689490706572e-22,1744061308.6550884,3.0214710235595703,2.355841557084658,1744061308.655091,3.0214710235595703,0.0,1744061308.6550925,3.0214710235595703,-22627416996.08485,1744061308.655094,3.0214710235595703,0.0,1744061308.6550953,3.0214710235595703,28284271247.461903
+1744061308.6747303,3.04148530960083,0.06277094660244345,1744061308.674732,3.04148530960083,-0.009242870528550958,1744061308.6747344,3.04148530960083,0.021874197304972032,1744061308.674736,3.04148530960083,-56568542383.61566,1744061308.6747375,3.04148530960083,0.065,1744061308.6747384,3.04148530960083,3.141592653588481,1744061308.6747394,3.04148530960083,0.07424089894901968,1744061308.6747406,3.04148530960083,1.0690689490706572e-22,1744061308.6747415,3.04148530960083,2.355841557084658,1744061308.674743,3.04148530960083,0.0,1744061308.6747441,3.04148530960083,-22627416996.08485,1744061308.674745,3.04148530960083,0.0,1744061308.674746,3.04148530960083,28284271247.461903
+1744061308.6947393,3.061478853225708,0.06277094660244345,1744061308.694742,3.061478853225708,-0.009242870528550958,1744061308.6947446,3.061478853225708,0.021874197304972032,1744061308.6947472,3.061478853225708,-56568542383.61566,1744061308.6947486,3.061478853225708,0.065,1744061308.6947503,3.061478853225708,3.141592653588481,1744061308.6947517,3.061478853225708,0.07424089894901968,1744061308.694753,3.061478853225708,1.0690689490706572e-22,1744061308.6947546,3.061478853225708,2.355841557084658,1744061308.694756,3.061478853225708,0.0,1744061308.6947575,3.061478853225708,-22627416996.08485,1744061308.6947584,3.061478853225708,0.0,1744061308.6947596,3.061478853225708,28284271247.461903
+1744061308.715056,3.08148455619812,0.06277094660244345,1744061308.7150576,3.08148455619812,-0.009242870528550958,1744061308.7150598,3.08148455619812,0.021874197304972032,1744061308.7150617,3.08148455619812,-56568542383.61566,1744061308.7150629,3.08148455619812,0.065,1744061308.715064,3.08148455619812,3.141592653588481,1744061308.715065,3.08148455619812,0.07424089894901968,1744061308.7150662,3.08148455619812,1.0690689490706572e-22,1744061308.715067,3.08148455619812,2.355841557084658,1744061308.7150686,3.08148455619812,0.0,1744061308.7150695,3.08148455619812,-22627416996.08485,1744061308.7150707,3.08148455619812,0.0,1744061308.7150717,3.08148455619812,28284271247.461903
+1744061308.735119,3.101470708847046,0.06277094660244345,1744061308.7351205,3.101470708847046,-0.009242870528550958,1744061308.7351227,3.101470708847046,0.021874197304972032,1744061308.7351246,3.101470708847046,-56568542383.61566,1744061308.7351255,3.101470708847046,0.065,1744061308.7351267,3.101470708847046,3.141592653588481,1744061308.735128,3.101470708847046,0.07424089894901968,1744061308.7351289,3.101470708847046,1.0690689490706572e-22,1744061308.7351296,3.101470708847046,2.355841557084658,1744061308.7351308,3.101470708847046,0.0,1744061308.7351317,3.101470708847046,-22627416996.08485,1744061308.7351327,3.101470708847046,0.0,1744061308.7351336,3.101470708847046,28284271247.461903
+1744061308.7564235,3.1215343475341797,0.06277094660244345,1744061308.7564292,3.1215343475341797,-0.009242870528550958,1744061308.7564342,3.1215343475341797,0.021874197304972032,1744061308.7564373,3.1215343475341797,-56568542383.61566,1744061308.75644,3.1215343475341797,0.065,1744061308.7564423,3.1215343475341797,3.141592653588481,1744061308.7564442,3.1215343475341797,0.07424089894901968,1744061308.7564456,3.1215343475341797,1.0690689490706572e-22,1744061308.7564483,3.1215343475341797,2.355841557084658,1744061308.7564518,3.1215343475341797,0.0,1744061308.756454,3.1215343475341797,-22627416996.08485,1744061308.7564557,3.1215343475341797,0.0,1744061308.7564576,3.1215343475341797,28284271247.461903
+1744061308.7748072,3.1414949893951416,0.06277094660244345,1744061308.7748094,3.1414949893951416,-0.009242870528550958,1744061308.7748115,3.1414949893951416,0.021874197304972032,1744061308.7748134,3.1414949893951416,-56568542383.61566,1744061308.7748144,3.1414949893951416,0.065,1744061308.774816,3.1414949893951416,3.141592653588481,1744061308.774817,3.1414949893951416,0.07424089894901968,1744061308.774818,3.1414949893951416,1.0690689490706572e-22,1744061308.7748191,3.1414949893951416,2.355841557084658,1744061308.7748206,3.1414949893951416,0.0,1744061308.7748213,3.1414949893951416,-22627416996.08485,1744061308.7748227,3.1414949893951416,0.0,1744061308.7748234,3.1414949893951416,28284271247.461903
+1744061308.7947304,3.1614556312561035,0.06277094660244345,1744061308.7947323,3.1614556312561035,-0.009242870528550958,1744061308.7947342,3.1614556312561035,0.021874197304972032,1744061308.7947364,3.1614556312561035,-56568542383.61566,1744061308.7947376,3.1614556312561035,0.065,1744061308.794739,3.1614556312561035,3.141592653588481,1744061308.79474,3.1614556312561035,0.07424089894901968,1744061308.794741,3.1614556312561035,1.0690689490706572e-22,1744061308.794742,3.1614556312561035,2.355841557084658,1744061308.7947435,3.1614556312561035,0.0,1744061308.7947443,3.1614556312561035,-22627416996.08485,1744061308.7947457,3.1614556312561035,0.0,1744061308.7947464,3.1614556312561035,28284271247.461903
+1744061308.8165677,3.1820461750030518,0.06277094660244345,1744061308.8165739,3.1820461750030518,-0.009242870528550958,1744061308.8165789,3.1820461750030518,0.021874197304972032,1744061308.8165815,3.1820461750030518,-56568542383.61566,1744061308.816583,3.1820461750030518,0.065,1744061308.8165846,3.1820461750030518,3.141592653588481,1744061308.816587,3.1820461750030518,0.07424089894901968,1744061308.816588,3.1820461750030518,1.0690689490706572e-22,1744061308.8165896,3.1820461750030518,2.355841557084658,1744061308.816592,3.1820461750030518,0.0,1744061308.8165934,3.1820461750030518,-22627416996.08485,1744061308.8165953,3.1820461750030518,0.0,1744061308.816597,3.1820461750030518,28284271247.461903
+1744061308.8352377,3.2014541625976562,0.07068912291155344,1744061308.8352394,3.2014541625976562,-0.007658543815406944,1744061308.8352416,3.2014541625976562,0.02195337906806313,1744061308.8352435,3.2014541625976562,-56568542383.61574,1744061308.8352447,3.2014541625976562,0.065,1744061308.8352458,3.2014541625976562,3.141592653588509,1744061308.835247,3.2014541625976562,0.07265824575378907,1744061308.8352478,3.2014541625976562,1.0462787429694044e-22,1744061308.835249,3.2014541625976562,2.3588262303012013,1744061308.8352504,3.2014541625976562,0.0,1744061308.835251,3.2014541625976562,-22627416996.081566,1744061308.8352523,3.2014541625976562,0.0,1744061308.8352532,3.2014541625976562,28284271247.461903
+1744061308.8547568,3.2215116024017334,0.07068912291155344,1744061308.854759,3.2215116024017334,-0.007658543815406944,1744061308.854761,3.2215116024017334,0.02195337906806313,1744061308.8547633,3.2215116024017334,-56568542383.61574,1744061308.8547645,3.2215116024017334,0.065,1744061308.854766,3.2215116024017334,3.141592653588509,1744061308.8547668,3.2215116024017334,0.07265824575378907,1744061308.8547678,3.2215116024017334,1.0462787429694044e-22,1744061308.854769,3.2215116024017334,2.3588262303012013,1744061308.8547704,3.2215116024017334,0.0,1744061308.8547711,3.2215116024017334,-22627416996.082462,1744061308.8547726,3.2215116024017334,0.0,1744061308.8547733,3.2215116024017334,28284271247.461903
+1744061308.874812,3.2414493560791016,0.07068912291155344,1744061308.874814,3.2414493560791016,-0.007658543815406944,1744061308.8748157,3.2414493560791016,0.02195337906806313,1744061308.8748178,3.2414493560791016,-56568542383.61574,1744061308.8748188,3.2414493560791016,0.065,1744061308.87482,3.2414493560791016,3.141592653588509,1744061308.8748212,3.2414493560791016,0.07265824575378907,1744061308.8748221,3.2414493560791016,1.0462787429694044e-22,1744061308.874823,3.2414493560791016,2.3588262303012013,1744061308.8748245,3.2414493560791016,0.0,1744061308.8748255,3.2414493560791016,-22627416996.082462,1744061308.8748264,3.2414493560791016,0.0,1744061308.8748276,3.2414493560791016,28284271247.461903
+1744061308.8947208,3.261446952819824,0.07068912291155344,1744061308.8947225,3.261446952819824,-0.007658543815406944,1744061308.8947246,3.261446952819824,0.02195337906806313,1744061308.8947268,3.261446952819824,-56568542383.61574,1744061308.894728,3.261446952819824,0.065,1744061308.8947291,3.261446952819824,3.141592653588509,1744061308.8947303,3.261446952819824,0.07265824575378907,1744061308.8947313,3.261446952819824,1.0462787429694044e-22,1744061308.8947322,3.261446952819824,2.3588262303012013,1744061308.894734,3.261446952819824,0.0,1744061308.8947349,3.261446952819824,-22627416996.082462,1744061308.894736,3.261446952819824,0.0,1744061308.894737,3.261446952819824,28284271247.461903
+1744061308.9146962,3.2814877033233643,0.07068912291155344,1744061308.9146988,3.2814877033233643,-0.007658543815406944,1744061308.9147022,3.2814877033233643,0.02195337906806313,1744061308.9147048,3.2814877033233643,-56568542383.61574,1744061308.914706,3.2814877033233643,0.065,1744061308.9147072,3.2814877033233643,3.141592653588509,1744061308.9147081,3.2814877033233643,0.07265824575378907,1744061308.9147093,3.2814877033233643,1.0462787429694044e-22,1744061308.9147103,3.2814877033233643,2.3588262303012013,1744061308.9147115,3.2814877033233643,0.0,1744061308.9147127,3.2814877033233643,-22627416996.082462,1744061308.9147136,3.2814877033233643,0.0,1744061308.9147146,3.2814877033233643,28284271247.461903
+1744061308.934936,3.301454782485962,0.07068912291155344,1744061308.934938,3.301454782485962,-0.007658543815406944,1744061308.9349399,3.301454782485962,0.02195337906806313,1744061308.934942,3.301454782485962,-56568542383.61574,1744061308.9349432,3.301454782485962,0.065,1744061308.9349442,3.301454782485962,3.141592653588509,1744061308.9349456,3.301454782485962,0.07265824575378907,1744061308.9349463,3.301454782485962,1.0462787429694044e-22,1744061308.9349473,3.301454782485962,2.3588262303012013,1744061308.9349487,3.301454782485962,0.0,1744061308.9349494,3.301454782485962,-22627416996.082462,1744061308.9349504,3.301454782485962,0.0,1744061308.9349513,3.301454782485962,28284271247.461903
+1744061308.9549086,3.321460723876953,0.07068912291155344,1744061308.9549108,3.321460723876953,-0.007658543815406944,1744061308.9549134,3.321460723876953,0.02195337906806313,1744061308.9549153,3.321460723876953,-56568542383.61574,1744061308.954917,3.321460723876953,0.065,1744061308.9549186,3.321460723876953,3.141592653588509,1744061308.95492,3.321460723876953,0.07265824575378907,1744061308.954921,3.321460723876953,1.0462787429694044e-22,1744061308.9549222,3.321460723876953,2.3588262303012013,1744061308.9549236,3.321460723876953,0.0,1744061308.9549246,3.321460723876953,-22627416996.082462,1744061308.9549255,3.321460723876953,0.0,1744061308.9549267,3.321460723876953,28284271247.461903
+1744061308.9747608,3.3414793014526367,0.07068912291155344,1744061308.9747627,3.3414793014526367,-0.007658543815406944,1744061308.974765,3.3414793014526367,0.02195337906806313,1744061308.9747674,3.3414793014526367,-56568542383.61574,1744061308.9747684,3.3414793014526367,0.065,1744061308.9747696,3.3414793014526367,3.141592653588509,1744061308.9747708,3.3414793014526367,0.07265824575378907,1744061308.9747717,3.3414793014526367,1.0462787429694044e-22,1744061308.9747727,3.3414793014526367,2.3588262303012013,1744061308.9747741,3.3414793014526367,0.0,1744061308.974775,3.3414793014526367,-22627416996.082462,1744061308.9747763,3.3414793014526367,0.0,1744061308.974777,3.3414793014526367,28284271247.461903
+1744061308.9947057,3.3614535331726074,0.07068912291155344,1744061308.9947073,3.3614535331726074,-0.007658543815406944,1744061308.9947095,3.3614535331726074,0.02195337906806313,1744061308.9947116,3.3614535331726074,-56568542383.61574,1744061308.9947126,3.3614535331726074,0.065,1744061308.9947135,3.3614535331726074,3.141592653588509,1744061308.9947147,3.3614535331726074,0.07265824575378907,1744061308.9947157,3.3614535331726074,1.0462787429694044e-22,1744061308.9947164,3.3614535331726074,2.3588262303012013,1744061308.9947176,3.3614535331726074,0.0,1744061308.9947188,3.3614535331726074,-22627416996.082462,1744061308.9947197,3.3614535331726074,0.0,1744061308.9947207,3.3614535331726074,28284271247.461903
+1744061309.014697,3.3814804553985596,0.07068912291155344,1744061309.0146987,3.3814804553985596,-0.007658543815406944,1744061309.014701,3.3814804553985596,0.02195337906806313,1744061309.0147026,3.3814804553985596,-56568542383.61574,1744061309.014704,3.3814804553985596,0.065,1744061309.014705,3.3814804553985596,3.141592653588509,1744061309.014706,3.3814804553985596,0.07265824575378907,1744061309.0147069,3.3814804553985596,1.0462787429694044e-22,1744061309.0147078,3.3814804553985596,2.3588262303012013,1744061309.014709,3.3814804553985596,0.0,1744061309.01471,3.3814804553985596,-22627416996.082462,1744061309.0147111,3.3814804553985596,0.0,1744061309.014712,3.3814804553985596,28284271247.461903
+1744061309.0350082,3.401493549346924,0.07068912291155344,1744061309.0350099,3.401493549346924,-0.007658543815406944,1744061309.035012,3.401493549346924,0.02195337906806313,1744061309.0350142,3.401493549346924,-56568542383.61574,1744061309.035015,3.401493549346924,0.065,1744061309.0350163,3.401493549346924,3.141592653588509,1744061309.0350175,3.401493549346924,0.07265824575378907,1744061309.0350182,3.401493549346924,1.0462787429694044e-22,1744061309.0350192,3.401493549346924,2.3588262303012013,1744061309.0350206,3.401493549346924,0.0,1744061309.0350213,3.401493549346924,-22627416996.082462,1744061309.0350223,3.401493549346924,0.0,1744061309.0350235,3.401493549346924,28284271247.461903
+1744061309.0555031,3.421459197998047,0.07068912291155344,1744061309.0555065,3.421459197998047,-0.007658543815406944,1744061309.0555103,3.421459197998047,0.02195337906806313,1744061309.0555136,3.421459197998047,-56568542383.61574,1744061309.0555158,3.421459197998047,0.065,1744061309.055518,3.421459197998047,3.141592653588509,1744061309.0555203,3.421459197998047,0.07265824575378907,1744061309.0555217,3.421459197998047,1.0462787429694044e-22,1744061309.0555239,3.421459197998047,2.3588262303012013,1744061309.0555267,3.421459197998047,0.0,1744061309.0555286,3.421459197998047,-22627416996.082462,1744061309.0555305,3.421459197998047,0.0,1744061309.055532,3.421459197998047,28284271247.461903
+1744061309.074744,3.4414796829223633,0.07068912291155344,1744061309.074746,3.4414796829223633,-0.007658543815406944,1744061309.0747483,3.4414796829223633,0.02195337906806313,1744061309.0747502,3.4414796829223633,-56568542383.61574,1744061309.0747511,3.4414796829223633,0.065,1744061309.0747533,3.4414796829223633,3.141592653588509,1744061309.0747545,3.4414796829223633,0.07265824575378907,1744061309.0747554,3.4414796829223633,1.0462787429694044e-22,1744061309.0747566,3.4414796829223633,2.3588262303012013,1744061309.074758,3.4414796829223633,0.0,1744061309.0747592,3.4414796829223633,-22627416996.082462,1744061309.0747607,3.4414796829223633,0.0,1744061309.0747616,3.4414796829223633,28284271247.461903
+1744061309.0950346,3.461493730545044,0.07068912291155344,1744061309.0950365,3.461493730545044,-0.007658543815406944,1744061309.0950384,3.461493730545044,0.02195337906806313,1744061309.0950406,3.461493730545044,-56568542383.61574,1744061309.0950415,3.461493730545044,0.065,1744061309.0950427,3.461493730545044,3.141592653588509,1744061309.095044,3.461493730545044,0.07265824575378907,1744061309.0950446,3.461493730545044,1.0462787429694044e-22,1744061309.0950456,3.461493730545044,2.3588262303012013,1744061309.0950472,3.461493730545044,0.0,1744061309.0950482,3.461493730545044,-22627416996.082462,1744061309.0950491,3.461493730545044,0.0,1744061309.0950503,3.461493730545044,28284271247.461903
+1744061309.1148803,3.481445550918579,0.07068912291155344,1744061309.114882,3.481445550918579,-0.007658543815406944,1744061309.1148841,3.481445550918579,0.02195337906806313,1744061309.114886,3.481445550918579,-56568542383.61574,1744061309.1148872,3.481445550918579,0.065,1744061309.1148884,3.481445550918579,3.141592653588509,1744061309.1148894,3.481445550918579,0.07265824575378907,1744061309.1148906,3.481445550918579,1.0462787429694044e-22,1744061309.1148913,3.481445550918579,2.3588262303012013,1744061309.1148925,3.481445550918579,0.0,1744061309.1148937,3.481445550918579,-22627416996.082462,1744061309.1148946,3.481445550918579,0.0,1744061309.1148953,3.481445550918579,28284271247.461903
+1744061309.1349082,3.501451253890991,0.07068912291155344,1744061309.1349099,3.501451253890991,-0.007658543815406944,1744061309.134912,3.501451253890991,0.02195337906806313,1744061309.1349137,3.501451253890991,-56568542383.61574,1744061309.134915,3.501451253890991,0.065,1744061309.134916,3.501451253890991,3.141592653588509,1744061309.134917,3.501451253890991,0.07265824575378907,1744061309.1349182,3.501451253890991,1.0462787429694044e-22,1744061309.1349192,3.501451253890991,2.3588262303012013,1744061309.1349201,3.501451253890991,0.0,1744061309.1349213,3.501451253890991,-22627416996.082462,1744061309.1349223,3.501451253890991,0.0,1744061309.134923,3.501451253890991,28284271247.461903
+1744061309.154752,3.5214459896087646,0.07068912291155344,1744061309.1547704,3.5214459896087646,-0.007658543815406944,1744061309.1547728,3.5214459896087646,0.02195337906806313,1744061309.1547744,3.5214459896087646,-56568542383.61574,1744061309.1547759,3.5214459896087646,0.065,1744061309.1547768,3.5214459896087646,3.141592653588509,1744061309.1547778,3.5214459896087646,0.07265824575378907,1744061309.154779,3.5214459896087646,1.0462787429694044e-22,1744061309.1547797,3.5214459896087646,2.3588262303012013,1744061309.1547813,3.5214459896087646,0.0,1744061309.1547823,3.5214459896087646,-22627416996.082462,1744061309.1547832,3.5214459896087646,0.0,1744061309.1547842,3.5214459896087646,28284271247.461903
+1744061309.1748934,3.5414795875549316,0.07068912291155344,1744061309.1748953,3.5414795875549316,-0.007658543815406944,1744061309.1748974,3.5414795875549316,0.02195337906806313,1744061309.174899,3.5414795875549316,-56568542383.61574,1744061309.1749005,3.5414795875549316,0.065,1744061309.1749017,3.5414795875549316,3.141592653588509,1744061309.1749027,3.5414795875549316,0.07265824575378907,1744061309.1749039,3.5414795875549316,1.0462787429694044e-22,1744061309.1749046,3.5414795875549316,2.3588262303012013,1744061309.1749063,3.5414795875549316,0.0,1744061309.1749074,3.5414795875549316,-22627416996.082462,1744061309.1749084,3.5414795875549316,0.0,1744061309.1749094,3.5414795875549316,28284271247.461903
+1744061309.194904,3.561528444290161,0.07068912291155344,1744061309.1949077,3.561528444290161,-0.007658543815406944,1744061309.19491,3.561528444290161,0.02195337906806313,1744061309.1949124,3.561528444290161,-56568542383.61574,1744061309.194914,3.561528444290161,0.065,1744061309.1949155,3.561528444290161,3.141592653588509,1744061309.1949172,3.561528444290161,0.07265824575378907,1744061309.1949184,3.561528444290161,1.0462787429694044e-22,1744061309.1949198,3.561528444290161,2.3588262303012013,1744061309.1949217,3.561528444290161,0.0,1744061309.1949227,3.561528444290161,-22627416996.082462,1744061309.194924,3.561528444290161,0.0,1744061309.194925,3.561528444290161,28284271247.461903
+1744061309.2147846,3.581486463546753,0.07068912291155344,1744061309.2147865,3.581486463546753,-0.007658543815406944,1744061309.2147887,3.581486463546753,0.02195337906806313,1744061309.2147906,3.581486463546753,-56568542383.61574,1744061309.214792,3.581486463546753,0.065,1744061309.2147932,3.581486463546753,3.141592653588509,1744061309.2147946,3.581486463546753,0.07265824575378907,1744061309.2147958,3.581486463546753,1.0462787429694044e-22,1744061309.2147965,3.581486463546753,2.3588262303012013,1744061309.2147985,3.581486463546753,0.0,1744061309.2147994,3.581486463546753,-22627416996.082462,1744061309.2148004,3.581486463546753,0.0,1744061309.214801,3.581486463546753,28284271247.461903
+1744061309.2350805,3.601468801498413,0.07068912291155344,1744061309.235082,3.601468801498413,-0.007658543815406944,1744061309.2350843,3.601468801498413,0.02195337906806313,1744061309.235086,3.601468801498413,-56568542383.61574,1744061309.2350872,3.601468801498413,0.065,1744061309.2350883,3.601468801498413,3.141592653588509,1744061309.2350893,3.601468801498413,0.07265824575378907,1744061309.2350903,3.601468801498413,1.0462787429694044e-22,1744061309.2350912,3.601468801498413,2.3588262303012013,1744061309.2350924,3.601468801498413,0.0,1744061309.2350934,3.601468801498413,-22627416996.082462,1744061309.2350943,3.601468801498413,0.0,1744061309.235095,3.601468801498413,28284271247.461903
+1744061309.2549694,3.62145733833313,0.07068912291155344,1744061309.2549722,3.62145733833313,-0.007658543815406944,1744061309.2549744,3.62145733833313,0.02195337906806313,1744061309.2549767,3.62145733833313,-56568542383.61574,1744061309.254978,3.62145733833313,0.065,1744061309.2549796,3.62145733833313,3.141592653588509,1744061309.2549808,3.62145733833313,0.07265824575378907,1744061309.254982,3.62145733833313,1.0462787429694044e-22,1744061309.2549832,3.62145733833313,2.3588262303012013,1744061309.2549849,3.62145733833313,0.0,1744061309.254986,3.62145733833313,-22627416996.082462,1744061309.2549872,3.62145733833313,0.0,1744061309.2549882,3.62145733833313,28284271247.461903
+1744061309.2746992,3.6414802074432373,0.07068912291155344,1744061309.274701,3.6414802074432373,-0.007658543815406944,1744061309.274703,3.6414802074432373,0.02195337906806313,1744061309.2747054,3.6414802074432373,-56568542383.61574,1744061309.2747066,3.6414802074432373,0.065,1744061309.274708,3.6414802074432373,3.141592653588509,1744061309.274709,3.6414802074432373,0.07265824575378907,1744061309.2747097,3.6414802074432373,1.0462787429694044e-22,1744061309.274711,3.6414802074432373,2.3588262303012013,1744061309.274712,3.6414802074432373,0.0,1744061309.2747128,3.6414802074432373,-22627416996.082462,1744061309.2747138,3.6414802074432373,0.0,1744061309.274715,3.6414802074432373,28284271247.461903
+1744061309.294737,3.6614956855773926,0.07068912291155344,1744061309.2947392,3.6614956855773926,-0.007658543815406944,1744061309.2947412,3.6614956855773926,0.02195337906806313,1744061309.2947433,3.6614956855773926,-56568542383.61574,1744061309.2947443,3.6614956855773926,0.065,1744061309.2947457,3.6614956855773926,3.141592653588509,1744061309.2947469,3.6614956855773926,0.07265824575378907,1744061309.2947476,3.6614956855773926,1.0462787429694044e-22,1744061309.2947488,3.6614956855773926,2.3588262303012013,1744061309.2947502,3.6614956855773926,0.0,1744061309.2947512,3.6614956855773926,-22627416996.082462,1744061309.2947524,3.6614956855773926,0.0,1744061309.2947533,3.6614956855773926,28284271247.461903
+1744061309.314716,3.6814565658569336,0.07068912291155344,1744061309.314718,3.6814565658569336,-0.007658543815406944,1744061309.31472,3.6814565658569336,0.02195337906806313,1744061309.314722,3.6814565658569336,-56568542383.61574,1744061309.314723,3.6814565658569336,0.065,1744061309.3147244,3.6814565658569336,3.141592653588509,1744061309.3147254,3.6814565658569336,0.07265824575378907,1744061309.314726,3.6814565658569336,1.0462787429694044e-22,1744061309.314727,3.6814565658569336,2.3588262303012013,1744061309.3147285,3.6814565658569336,0.0,1744061309.3147295,3.6814565658569336,-22627416996.082462,1744061309.3147304,3.6814565658569336,0.0,1744061309.3147314,3.6814565658569336,28284271247.461903
+1744061309.3349316,3.701446771621704,0.07487429048714508,1744061309.3349335,3.701446771621704,-0.01458811031126979,1744061309.3349357,3.701446771621704,0.021995230743819046,1744061309.3349376,3.701446771621704,-56568542383.61578,1744061309.3349385,3.701446771621704,0.065,1744061309.3349402,3.701446771621704,3.1415926535883862,1744061309.3349411,3.701446771621704,0.07959177403770837,1744061309.3349419,3.701446771621704,1.1461215506503361e-22,1744061309.334943,3.701446771621704,2.345778459881227,1744061309.3349442,3.701446771621704,0.0,1744061309.334945,3.701446771621704,-22627416996.09682,1744061309.3349462,3.701446771621704,0.0,1744061309.334947,3.701446771621704,28284271247.461903
+1744061309.355267,3.721510171890259,0.07487429048714508,1744061309.355269,3.721510171890259,-0.01458811031126979,1744061309.3552709,3.721510171890259,0.021995230743819046,1744061309.355273,3.721510171890259,-56568542383.61578,1744061309.355274,3.721510171890259,0.065,1744061309.3552752,3.721510171890259,3.1415926535883862,1744061309.3552766,3.721510171890259,0.07959177403770837,1744061309.3552775,3.721510171890259,1.1461215506503361e-22,1744061309.3552785,3.721510171890259,2.345778459881227,1744061309.3552802,3.721510171890259,0.0,1744061309.355281,3.721510171890259,-22627416996.0929,1744061309.355282,3.721510171890259,0.0,1744061309.3552833,3.721510171890259,28284271247.461903
+1744061309.37474,3.741492509841919,0.07487429048714508,1744061309.3747418,3.741492509841919,-0.01458811031126979,1744061309.3747437,3.741492509841919,0.021995230743819046,1744061309.3747458,3.741492509841919,-56568542383.61578,1744061309.3747468,3.741492509841919,0.065,1744061309.3747485,3.741492509841919,3.1415926535883862,1744061309.3747494,3.741492509841919,0.07959177403770837,1744061309.3747501,3.741492509841919,1.1461215506503361e-22,1744061309.3747513,3.741492509841919,2.345778459881227,1744061309.3747528,3.741492509841919,0.0,1744061309.3747537,3.741492509841919,-22627416996.0929,1744061309.374755,3.741492509841919,0.0,1744061309.3747559,3.741492509841919,28284271247.461903
+1744061309.3946834,3.76145339012146,0.07487429048714508,1744061309.3946853,3.76145339012146,-0.01458811031126979,1744061309.3946872,3.76145339012146,0.021995230743819046,1744061309.3946893,3.76145339012146,-56568542383.61578,1744061309.3946903,3.76145339012146,0.065,1744061309.3946915,3.76145339012146,3.1415926535883862,1744061309.394693,3.76145339012146,0.07959177403770837,1744061309.3946939,3.76145339012146,1.1461215506503361e-22,1744061309.3946948,3.76145339012146,2.345778459881227,1744061309.3946962,3.76145339012146,0.0,1744061309.3946972,3.76145339012146,-22627416996.0929,1744061309.3946984,3.76145339012146,0.0,1744061309.3946996,3.76145339012146,28284271247.461903
+1744061309.4147768,3.7815070152282715,0.07487429048714508,1744061309.4147787,3.7815070152282715,-0.01458811031126979,1744061309.4147806,3.7815070152282715,0.021995230743819046,1744061309.4147828,3.7815070152282715,-56568542383.61578,1744061309.4147837,3.7815070152282715,0.065,1744061309.4147854,3.7815070152282715,3.1415926535883862,1744061309.4147863,3.7815070152282715,0.07959177403770837,1744061309.4147873,3.7815070152282715,1.1461215506503361e-22,1744061309.4147882,3.7815070152282715,2.345778459881227,1744061309.4147897,3.7815070152282715,0.0,1744061309.4147909,3.7815070152282715,-22627416996.0929,1744061309.4147918,3.7815070152282715,0.0,1744061309.414793,3.7815070152282715,28284271247.461903
+1744061309.434912,3.8014464378356934,0.07487429048714508,1744061309.4349139,3.8014464378356934,-0.01458811031126979,1744061309.4349158,3.8014464378356934,0.021995230743819046,1744061309.434918,3.8014464378356934,-56568542383.61578,1744061309.4349189,3.8014464378356934,0.065,1744061309.4349203,3.8014464378356934,3.1415926535883862,1744061309.4349213,3.8014464378356934,0.07959177403770837,1744061309.434922,3.8014464378356934,1.1461215506503361e-22,1744061309.434923,3.8014464378356934,2.345778459881227,1744061309.4349246,3.8014464378356934,0.0,1744061309.4349253,3.8014464378356934,-22627416996.0929,1744061309.4349263,3.8014464378356934,0.0,1744061309.4349275,3.8014464378356934,28284271247.461903
+1744061309.4549885,3.821467638015747,0.07487429048714508,1744061309.4549913,3.821467638015747,-0.01458811031126979,1744061309.4549937,3.821467638015747,0.021995230743819046,1744061309.4549956,3.821467638015747,-56568542383.61578,1744061309.4549968,3.821467638015747,0.065,1744061309.454998,3.821467638015747,3.1415926535883862,1744061309.4549992,3.821467638015747,0.07959177403770837,1744061309.4550002,3.821467638015747,1.1461215506503361e-22,1744061309.455001,3.821467638015747,2.345778459881227,1744061309.4550028,3.821467638015747,0.0,1744061309.4550037,3.821467638015747,-22627416996.0929,1744061309.455005,3.821467638015747,0.0,1744061309.4550056,3.821467638015747,28284271247.461903
+1744061309.4748273,3.8414552211761475,0.07487429048714508,1744061309.4748292,3.8414552211761475,-0.01458811031126979,1744061309.4748313,3.8414552211761475,0.021995230743819046,1744061309.4748335,3.8414552211761475,-56568542383.61578,1744061309.4748344,3.8414552211761475,0.065,1744061309.4748359,3.8414552211761475,3.1415926535883862,1744061309.474837,3.8414552211761475,0.07959177403770837,1744061309.4748378,3.8414552211761475,1.1461215506503361e-22,1744061309.4748387,3.8414552211761475,2.345778459881227,1744061309.4748402,3.8414552211761475,0.0,1744061309.474841,3.8414552211761475,-22627416996.0929,1744061309.474842,3.8414552211761475,0.0,1744061309.474843,3.8414552211761475,28284271247.461903
+1744061309.4957423,3.8615963459014893,0.07487429048714508,1744061309.4957464,3.8615963459014893,-0.01458811031126979,1744061309.4957504,3.8615963459014893,0.021995230743819046,1744061309.4957533,3.8615963459014893,-56568542383.61578,1744061309.4957557,3.8615963459014893,0.065,1744061309.4957588,3.8615963459014893,3.1415926535883862,1744061309.4957604,3.8615963459014893,0.07959177403770837,1744061309.4957616,3.8615963459014893,1.1461215506503361e-22,1744061309.4957633,3.8615963459014893,2.345778459881227,1744061309.4957676,3.8615963459014893,0.0,1744061309.4957688,3.8615963459014893,-22627416996.0929,1744061309.4957697,3.8615963459014893,0.0,1744061309.495772,3.8615963459014893,28284271247.461903
+1744061309.5147667,3.881491184234619,0.07487429048714508,1744061309.5147688,3.881491184234619,-0.01458811031126979,1744061309.514771,3.881491184234619,0.021995230743819046,1744061309.514773,3.881491184234619,-56568542383.61578,1744061309.5147743,3.881491184234619,0.065,1744061309.5147755,3.881491184234619,3.1415926535883862,1744061309.5147765,3.881491184234619,0.07959177403770837,1744061309.5147774,3.881491184234619,1.1461215506503361e-22,1744061309.5147784,3.881491184234619,2.345778459881227,1744061309.5147798,3.881491184234619,0.0,1744061309.5147808,3.881491184234619,-22627416996.0929,1744061309.5147817,3.881491184234619,0.0,1744061309.5147827,3.881491184234619,28284271247.461903
+1744061309.5348735,3.9014768600463867,0.07487429048714508,1744061309.5348752,3.9014768600463867,-0.01458811031126979,1744061309.5348773,3.9014768600463867,0.021995230743819046,1744061309.5348792,3.9014768600463867,-56568542383.61578,1744061309.5348802,3.9014768600463867,0.065,1744061309.5348818,3.9014768600463867,3.1415926535883862,1744061309.5348828,3.9014768600463867,0.07959177403770837,1744061309.5348835,3.9014768600463867,1.1461215506503361e-22,1744061309.5348847,3.9014768600463867,2.345778459881227,1744061309.534886,3.9014768600463867,0.0,1744061309.5348866,3.9014768600463867,-22627416996.0929,1744061309.5348878,3.9014768600463867,0.0,1744061309.5348887,3.9014768600463867,28284271247.461903
+1744061309.5553184,3.921471118927002,0.07487429048714508,1744061309.5553231,3.921471118927002,-0.01458811031126979,1744061309.5553272,3.921471118927002,0.021995230743819046,1744061309.5553312,3.921471118927002,-56568542383.61578,1744061309.5553334,3.921471118927002,0.065,1744061309.555337,3.921471118927002,3.1415926535883862,1744061309.5553396,3.921471118927002,0.07959177403770837,1744061309.555341,3.921471118927002,1.1461215506503361e-22,1744061309.5553439,3.921471118927002,2.345778459881227,1744061309.5553489,3.921471118927002,0.0,1744061309.555351,3.921471118927002,-22627416996.0929,1744061309.5553536,3.921471118927002,0.0,1744061309.555355,3.921471118927002,28284271247.461903
+1744061309.5747778,3.941471576690674,0.07487429048714508,1744061309.5747797,3.941471576690674,-0.01458811031126979,1744061309.5747817,3.941471576690674,0.021995230743819046,1744061309.5747843,3.941471576690674,-56568542383.61578,1744061309.5747852,3.941471576690674,0.065,1744061309.5747867,3.941471576690674,3.1415926535883862,1744061309.5747876,3.941471576690674,0.07959177403770837,1744061309.5747883,3.941471576690674,1.1461215506503361e-22,1744061309.5747893,3.941471576690674,2.345778459881227,1744061309.574791,3.941471576690674,0.0,1744061309.574792,3.941471576690674,-22627416996.0929,1744061309.574793,3.941471576690674,0.0,1744061309.5747943,3.941471576690674,28284271247.461903
+1744061309.594691,3.961455821990967,0.07487429048714508,1744061309.5947113,3.961455821990967,-0.01458811031126979,1744061309.5947137,3.961455821990967,0.021995230743819046,1744061309.5947156,3.961455821990967,-56568542383.61578,1744061309.5947168,3.961455821990967,0.065,1744061309.594718,3.961455821990967,3.1415926535883862,1744061309.594719,3.961455821990967,0.07959177403770837,1744061309.59472,3.961455821990967,1.1461215506503361e-22,1744061309.5947394,3.961455821990967,2.345778459881227,1744061309.5947406,3.961455821990967,0.0,1744061309.5947418,3.961455821990967,-22627416996.0929,1744061309.5947428,3.961455821990967,0.0,1744061309.5947437,3.961455821990967,28284271247.461903
+1744061309.614867,3.981462001800537,0.07487429048714508,1744061309.6148698,3.981462001800537,-0.01458811031126979,1744061309.6148717,3.981462001800537,0.021995230743819046,1744061309.6148744,3.981462001800537,-56568542383.61578,1744061309.6148756,3.981462001800537,0.065,1744061309.6148775,3.981462001800537,3.1415926535883862,1744061309.6148784,3.981462001800537,0.07959177403770837,1744061309.6148794,3.981462001800537,1.1461215506503361e-22,1744061309.6148806,3.981462001800537,2.345778459881227,1744061309.614882,3.981462001800537,0.0,1744061309.6148832,3.981462001800537,-22627416996.0929,1744061309.6148841,3.981462001800537,0.0,1744061309.614885,3.981462001800537,28284271247.461903
+1744061309.635071,4.001483917236328,0.07487429048714508,1744061309.6350727,4.001483917236328,-0.01458811031126979,1744061309.6350753,4.001483917236328,0.021995230743819046,1744061309.6350775,4.001483917236328,-56568542383.61578,1744061309.6350784,4.001483917236328,0.065,1744061309.6350796,4.001483917236328,3.1415926535883862,1744061309.6350808,4.001483917236328,0.07959177403770837,1744061309.6350815,4.001483917236328,1.1461215506503361e-22,1744061309.6350825,4.001483917236328,2.345778459881227,1744061309.6350837,4.001483917236328,0.0,1744061309.6350846,4.001483917236328,-22627416996.0929,1744061309.6350858,4.001483917236328,0.0,1744061309.6350865,4.001483917236328,28284271247.461903
+1744061309.6553504,4.021499395370483,0.07487429048714508,1744061309.6553547,4.021499395370483,-0.01458811031126979,1744061309.655377,4.021499395370483,0.021995230743819046,1744061309.6553802,4.021499395370483,-56568542383.61578,1744061309.6553817,4.021499395370483,0.065,1744061309.6553838,4.021499395370483,3.1415926535883862,1744061309.6553853,4.021499395370483,0.07959177403770837,1744061309.6553874,4.021499395370483,1.1461215506503361e-22,1744061309.6553898,4.021499395370483,2.345778459881227,1744061309.6554103,4.021499395370483,0.0,1744061309.6554122,4.021499395370483,-22627416996.0929,1744061309.6554139,4.021499395370483,0.0,1744061309.6554153,4.021499395370483,28284271247.461903
+1744061309.6747687,4.041446208953857,0.07487429048714508,1744061309.6747704,4.041446208953857,-0.01458811031126979,1744061309.6747725,4.041446208953857,0.021995230743819046,1744061309.6747746,4.041446208953857,-56568542383.61578,1744061309.6747756,4.041446208953857,0.065,1744061309.6747768,4.041446208953857,3.1415926535883862,1744061309.6747777,4.041446208953857,0.07959177403770837,1744061309.674779,4.041446208953857,1.1461215506503361e-22,1744061309.6747797,4.041446208953857,2.345778459881227,1744061309.674781,4.041446208953857,0.0,1744061309.6747823,4.041446208953857,-22627416996.0929,1744061309.6747835,4.041446208953857,0.0,1744061309.6747842,4.041446208953857,28284271247.461903
+1744061309.69493,4.061487197875977,0.07487429048714508,1744061309.6949325,4.061487197875977,-0.01458811031126979,1744061309.694935,4.061487197875977,0.021995230743819046,1744061309.6949372,4.061487197875977,-56568542383.61578,1744061309.6949387,4.061487197875977,0.065,1744061309.6949399,4.061487197875977,3.1415926535883862,1744061309.694941,4.061487197875977,0.07959177403770837,1744061309.694942,4.061487197875977,1.1461215506503361e-22,1744061309.6949427,4.061487197875977,2.345778459881227,1744061309.6949441,4.061487197875977,0.0,1744061309.6949453,4.061487197875977,-22627416996.0929,1744061309.6949463,4.061487197875977,0.0,1744061309.6949472,4.061487197875977,28284271247.461903
+1744061309.7147572,4.081486225128174,0.07487429048714508,1744061309.7147586,4.081486225128174,-0.01458811031126979,1744061309.7147613,4.081486225128174,0.021995230743819046,1744061309.7147632,4.081486225128174,-56568542383.61578,1744061309.7147644,4.081486225128174,0.065,1744061309.7147655,4.081486225128174,3.1415926535883862,1744061309.7147665,4.081486225128174,0.07959177403770837,1744061309.7147675,4.081486225128174,1.1461215506503361e-22,1744061309.7147684,4.081486225128174,2.345778459881227,1744061309.7147698,4.081486225128174,0.0,1744061309.7147708,4.081486225128174,-22627416996.0929,1744061309.7147717,4.081486225128174,0.0,1744061309.7147727,4.081486225128174,28284271247.461903
+1744061309.7354224,4.101518154144287,0.07487429048714508,1744061309.7354243,4.101518154144287,-0.01458811031126979,1744061309.7354262,4.101518154144287,0.021995230743819046,1744061309.7354283,4.101518154144287,-56568542383.61578,1744061309.7354293,4.101518154144287,0.065,1744061309.7354307,4.101518154144287,3.1415926535883862,1744061309.7354317,4.101518154144287,0.07959177403770837,1744061309.7354326,4.101518154144287,1.1461215506503361e-22,1744061309.7354338,4.101518154144287,2.345778459881227,1744061309.735435,4.101518154144287,0.0,1744061309.7354357,4.101518154144287,-22627416996.0929,1744061309.735437,4.101518154144287,0.0,1744061309.7354379,4.101518154144287,28284271247.461903
+1744061309.7548525,4.121467351913452,0.07487429048714508,1744061309.7548566,4.121467351913452,-0.01458811031126979,1744061309.75486,4.121467351913452,0.021995230743819046,1744061309.754863,4.121467351913452,-56568542383.61578,1744061309.7548656,4.121467351913452,0.065,1744061309.7548676,4.121467351913452,3.1415926535883862,1744061309.754869,4.121467351913452,0.07959177403770837,1744061309.75487,4.121467351913452,1.1461215506503361e-22,1744061309.754872,4.121467351913452,2.345778459881227,1744061309.7548892,4.121467351913452,0.0,1744061309.7548904,4.121467351913452,-22627416996.0929,1744061309.754892,4.121467351913452,0.0,1744061309.7548938,4.121467351913452,28284271247.461903
+1744061309.7750142,4.141494035720825,0.07487429048714508,1744061309.7750175,4.141494035720825,-0.01458811031126979,1744061309.7750227,4.141494035720825,0.021995230743819046,1744061309.7750275,4.141494035720825,-56568542383.61578,1744061309.77503,4.141494035720825,0.065,1744061309.7750323,4.141494035720825,3.1415926535883862,1744061309.7750347,4.141494035720825,0.07959177403770837,1744061309.775036,4.141494035720825,1.1461215506503361e-22,1744061309.7750385,4.141494035720825,2.345778459881227,1744061309.7750413,4.141494035720825,0.0,1744061309.7750437,4.141494035720825,-22627416996.0929,1744061309.7750463,4.141494035720825,0.0,1744061309.7750487,4.141494035720825,28284271247.461903
+1744061309.7951868,4.161529302597046,0.07487429048714508,1744061309.7951906,4.161529302597046,-0.01458811031126979,1744061309.7951927,4.161529302597046,0.021995230743819046,1744061309.795195,4.161529302597046,-56568542383.61578,1744061309.7951975,4.161529302597046,0.065,1744061309.7951994,4.161529302597046,3.1415926535883862,1744061309.7952015,4.161529302597046,0.07959177403770837,1744061309.7952025,4.161529302597046,1.1461215506503361e-22,1744061309.7952042,4.161529302597046,2.345778459881227,1744061309.795208,4.161529302597046,0.0,1744061309.7952092,4.161529302597046,-22627416996.0929,1744061309.7952106,4.161529302597046,0.0,1744061309.7952116,4.161529302597046,28284271247.461903
+1744061309.814666,4.181478261947632,0.07487429048714508,1744061309.8146677,4.181478261947632,-0.01458811031126979,1744061309.8146698,4.181478261947632,0.021995230743819046,1744061309.8146715,4.181478261947632,-56568542383.61578,1744061309.814673,4.181478261947632,0.065,1744061309.814674,4.181478261947632,3.1415926535883862,1744061309.8146749,4.181478261947632,0.07959177403770837,1744061309.814676,4.181478261947632,1.1461215506503361e-22,1744061309.814677,4.181478261947632,2.345778459881227,1744061309.8146782,4.181478261947632,0.0,1744061309.8146791,4.181478261947632,-22627416996.0929,1744061309.81468,4.181478261947632,0.0,1744061309.814681,4.181478261947632,28284271247.461903
+1744061309.8353314,4.201502561569214,0.0724504764386385,1744061309.8353333,4.201502561569214,-0.02168427894635568,1744061309.8353355,4.201502561569214,0.03228473117022809,1744061309.8353374,4.201502561569214,-56568542383.626076,1744061309.8353386,4.201502561569214,0.065,1744061309.8353398,4.201502561569214,3.141592653588261,1744061309.8353407,4.201502561569214,0.08667603119737154,1744061309.835342,4.201502561569214,1.2481348541503247e-22,1744061309.8353426,4.201502561569214,2.332521583134966,1744061309.8353438,4.201502561569214,0.0,1744061309.8353446,4.201502561569214,-22627416996.10749,1744061309.835346,4.201502561569214,0.0,1744061309.835347,4.201502561569214,28284271247.461903
+1744061309.8549376,4.221450328826904,0.0724504764386385,1744061309.8549395,4.221450328826904,-0.02168427894635568,1744061309.8549414,4.221450328826904,0.03228473117022809,1744061309.8549435,4.221450328826904,-56568542383.626076,1744061309.8549445,4.221450328826904,0.065,1744061309.8549461,4.221450328826904,3.141592653588261,1744061309.854947,4.221450328826904,0.08667603119737154,1744061309.8549478,4.221450328826904,1.2481348541503247e-22,1744061309.8549488,4.221450328826904,2.332521583134966,1744061309.8549502,4.221450328826904,0.0,1744061309.8549511,4.221450328826904,-22627416996.103504,1744061309.854952,4.221450328826904,0.0,1744061309.8549533,4.221450328826904,28284271247.461903
+1744061309.8747003,4.241453647613525,0.0724504764386385,1744061309.874702,4.241453647613525,-0.02168427894635568,1744061309.874704,4.241453647613525,0.03228473117022809,1744061309.874706,4.241453647613525,-56568542383.626076,1744061309.874707,4.241453647613525,0.065,1744061309.8747084,4.241453647613525,3.141592653588261,1744061309.8747091,4.241453647613525,0.08667603119737154,1744061309.8747103,4.241453647613525,1.2481348541503247e-22,1744061309.874711,4.241453647613525,2.332521583134966,1744061309.8747122,4.241453647613525,0.0,1744061309.8747134,4.241453647613525,-22627416996.103504,1744061309.8747144,4.241453647613525,0.0,1744061309.874715,4.241453647613525,28284271247.461903
+1744061309.8947551,4.261480808258057,0.0724504764386385,1744061309.894757,4.261480808258057,-0.02168427894635568,1744061309.8947592,4.261480808258057,0.03228473117022809,1744061309.8947613,4.261480808258057,-56568542383.626076,1744061309.8947625,4.261480808258057,0.065,1744061309.8947637,4.261480808258057,3.141592653588261,1744061309.894765,4.261480808258057,0.08667603119737154,1744061309.8947659,4.261480808258057,1.2481348541503247e-22,1744061309.8947668,4.261480808258057,2.332521583134966,1744061309.8947682,4.261480808258057,0.0,1744061309.8947694,4.261480808258057,-22627416996.103504,1744061309.8947704,4.261480808258057,0.0,1744061309.8947713,4.261480808258057,28284271247.461903
+1744061309.9147205,4.281456708908081,0.0724504764386385,1744061309.9147222,4.281456708908081,-0.02168427894635568,1744061309.9147246,4.281456708908081,0.03228473117022809,1744061309.9147265,4.281456708908081,-56568542383.626076,1744061309.9147277,4.281456708908081,0.065,1744061309.9147289,4.281456708908081,3.141592653588261,1744061309.91473,4.281456708908081,0.08667603119737154,1744061309.914731,4.281456708908081,1.2481348541503247e-22,1744061309.9147317,4.281456708908081,2.332521583134966,1744061309.9147332,4.281456708908081,0.0,1744061309.9147341,4.281456708908081,-22627416996.103504,1744061309.914735,4.281456708908081,0.0,1744061309.914736,4.281456708908081,28284271247.461903
+1744061309.935108,4.3015053272247314,0.0724504764386385,1744061309.9351096,4.3015053272247314,-0.02168427894635568,1744061309.9351118,4.3015053272247314,0.03228473117022809,1744061309.9351137,4.3015053272247314,-56568542383.626076,1744061309.9351149,4.3015053272247314,0.065,1744061309.9351158,4.3015053272247314,3.141592653588261,1744061309.9351168,4.3015053272247314,0.08667603119737154,1744061309.9351177,4.3015053272247314,1.2481348541503247e-22,1744061309.9351187,4.3015053272247314,2.332521583134966,1744061309.9351199,4.3015053272247314,0.0,1744061309.9351206,4.3015053272247314,-22627416996.103504,1744061309.9351218,4.3015053272247314,0.0,1744061309.9351227,4.3015053272247314,28284271247.461903
+1744061309.954718,4.32146692276001,0.0724504764386385,1744061309.9547203,4.32146692276001,-0.02168427894635568,1744061309.9547224,4.32146692276001,0.03228473117022809,1744061309.9547243,4.32146692276001,-56568542383.626076,1744061309.9547253,4.32146692276001,0.065,1744061309.9547267,4.32146692276001,3.141592653588261,1744061309.9547276,4.32146692276001,0.08667603119737154,1744061309.9547284,4.32146692276001,1.2481348541503247e-22,1744061309.9547296,4.32146692276001,2.332521583134966,1744061309.9547307,4.32146692276001,0.0,1744061309.9547315,4.32146692276001,-22627416996.103504,1744061309.9547327,4.32146692276001,0.0,1744061309.9547336,4.32146692276001,28284271247.461903
+1744061309.9747405,4.34148383140564,0.0724504764386385,1744061309.974742,4.34148383140564,-0.02168427894635568,1744061309.974744,4.34148383140564,0.03228473117022809,1744061309.9747458,4.34148383140564,-56568542383.626076,1744061309.974747,4.34148383140564,0.065,1744061309.9747484,4.34148383140564,3.141592653588261,1744061309.9747493,4.34148383140564,0.08667603119737154,1744061309.9747505,4.34148383140564,1.2481348541503247e-22,1744061309.9747515,4.34148383140564,2.332521583134966,1744061309.9747531,4.34148383140564,0.0,1744061309.9747539,4.34148383140564,-22627416996.103504,1744061309.974755,4.34148383140564,0.0,1744061309.974756,4.34148383140564,28284271247.461903
+1744061309.9951336,4.361476182937622,0.0724504764386385,1744061309.9951355,4.361476182937622,-0.02168427894635568,1744061309.9951377,4.361476182937622,0.03228473117022809,1744061309.9951398,4.361476182937622,-56568542383.626076,1744061309.9951408,4.361476182937622,0.065,1744061309.9951422,4.361476182937622,3.141592653588261,1744061309.9951432,4.361476182937622,0.08667603119737154,1744061309.995144,4.361476182937622,1.2481348541503247e-22,1744061309.9951448,4.361476182937622,2.332521583134966,1744061309.9951463,4.361476182937622,0.0,1744061309.995147,4.361476182937622,-22627416996.103504,1744061309.995148,4.361476182937622,0.0,1744061309.9951491,4.361476182937622,28284271247.461903
+1744061310.0148108,4.381483554840088,0.0724504764386385,1744061310.0148127,4.381483554840088,-0.02168427894635568,1744061310.0148144,4.381483554840088,0.03228473117022809,1744061310.0148165,4.381483554840088,-56568542383.626076,1744061310.0148175,4.381483554840088,0.065,1744061310.0148191,4.381483554840088,3.141592653588261,1744061310.01482,4.381483554840088,0.08667603119737154,1744061310.0148208,4.381483554840088,1.2481348541503247e-22,1744061310.014822,4.381483554840088,2.332521583134966,1744061310.0148234,4.381483554840088,0.0,1744061310.0148242,4.381483554840088,-22627416996.103504,1744061310.014825,4.381483554840088,0.0,1744061310.014826,4.381483554840088,28284271247.461903
+1744061310.0351012,4.40146541595459,0.0724504764386385,1744061310.0351038,4.40146541595459,-0.02168427894635568,1744061310.0351064,4.40146541595459,0.03228473117022809,1744061310.035108,4.40146541595459,-56568542383.626076,1744061310.0351102,4.40146541595459,0.065,1744061310.0351117,4.40146541595459,3.141592653588261,1744061310.0351129,4.40146541595459,0.08667603119737154,1744061310.0351138,4.40146541595459,1.2481348541503247e-22,1744061310.035115,4.40146541595459,2.332521583134966,1744061310.035117,4.40146541595459,0.0,1744061310.0351179,4.40146541595459,-22627416996.103504,1744061310.0351188,4.40146541595459,0.0,1744061310.0351198,4.40146541595459,28284271247.461903
+1744061310.054997,4.421489477157593,0.0724504764386385,1744061310.0549989,4.421489477157593,-0.02168427894635568,1744061310.055001,4.421489477157593,0.03228473117022809,1744061310.0550032,4.421489477157593,-56568542383.626076,1744061310.0550044,4.421489477157593,0.065,1744061310.0550058,4.421489477157593,3.141592653588261,1744061310.0550075,4.421489477157593,0.08667603119737154,1744061310.0550084,4.421489477157593,1.2481348541503247e-22,1744061310.0550096,4.421489477157593,2.332521583134966,1744061310.0550113,4.421489477157593,0.0,1744061310.0550125,4.421489477157593,-22627416996.103504,1744061310.0550134,4.421489477157593,0.0,1744061310.0550144,4.421489477157593,28284271247.461903
+1744061310.0746748,4.441479206085205,0.0724504764386385,1744061310.0746768,4.441479206085205,-0.02168427894635568,1744061310.074679,4.441479206085205,0.03228473117022809,1744061310.0746808,4.441479206085205,-56568542383.626076,1744061310.0746818,4.441479206085205,0.065,1744061310.0746832,4.441479206085205,3.141592653588261,1744061310.0746841,4.441479206085205,0.08667603119737154,1744061310.0746849,4.441479206085205,1.2481348541503247e-22,1744061310.0746863,4.441479206085205,2.332521583134966,1744061310.0746872,4.441479206085205,0.0,1744061310.0746882,4.441479206085205,-22627416996.103504,1744061310.0746894,4.441479206085205,0.0,1744061310.07469,4.441479206085205,28284271247.461903
+1744061310.095114,4.461481332778931,0.0724504764386385,1744061310.0951164,4.461481332778931,-0.02168427894635568,1744061310.0951185,4.461481332778931,0.03228473117022809,1744061310.095121,4.461481332778931,-56568542383.626076,1744061310.0951223,4.461481332778931,0.065,1744061310.0951245,4.461481332778931,3.141592653588261,1744061310.0951257,4.461481332778931,0.08667603119737154,1744061310.0951269,4.461481332778931,1.2481348541503247e-22,1744061310.095128,4.461481332778931,2.332521583134966,1744061310.0951302,4.461481332778931,0.0,1744061310.0951312,4.461481332778931,-22627416996.103504,1744061310.0951324,4.461481332778931,0.0,1744061310.0951338,4.461481332778931,28284271247.461903
+1744061310.1148374,4.481476068496704,0.0724504764386385,1744061310.1148396,4.481476068496704,-0.02168427894635568,1744061310.1148417,4.481476068496704,0.03228473117022809,1744061310.1148434,4.481476068496704,-56568542383.626076,1744061310.1148446,4.481476068496704,0.065,1744061310.114846,4.481476068496704,3.141592653588261,1744061310.114847,4.481476068496704,0.08667603119737154,1744061310.1148477,4.481476068496704,1.2481348541503247e-22,1744061310.114849,4.481476068496704,2.332521583134966,1744061310.1148503,4.481476068496704,0.0,1744061310.1148512,4.481476068496704,-22627416996.103504,1744061310.1148524,4.481476068496704,0.0,1744061310.1148534,4.481476068496704,28284271247.461903
+1744061310.1349282,4.501453399658203,0.0724504764386385,1744061310.13493,4.501453399658203,-0.02168427894635568,1744061310.134932,4.501453399658203,0.03228473117022809,1744061310.134934,4.501453399658203,-56568542383.626076,1744061310.1349351,4.501453399658203,0.065,1744061310.1349363,4.501453399658203,3.141592653588261,1744061310.1349373,4.501453399658203,0.08667603119737154,1744061310.134938,4.501453399658203,1.2481348541503247e-22,1744061310.1349392,4.501453399658203,2.332521583134966,1744061310.1349401,4.501453399658203,0.0,1744061310.134941,4.501453399658203,-22627416996.103504,1744061310.134942,4.501453399658203,0.0,1744061310.134943,4.501453399658203,28284271247.461903
+1744061310.1550267,4.5214762687683105,0.0724504764386385,1744061310.1550298,4.5214762687683105,-0.02168427894635568,1744061310.1550322,4.5214762687683105,0.03228473117022809,1744061310.1550343,4.5214762687683105,-56568542383.626076,1744061310.1550357,4.5214762687683105,0.065,1744061310.1550548,4.5214762687683105,3.141592653588261,1744061310.1550562,4.5214762687683105,0.08667603119737154,1744061310.1550574,4.5214762687683105,1.2481348541503247e-22,1744061310.1550584,4.5214762687683105,2.332521583134966,1744061310.1550605,4.5214762687683105,0.0,1744061310.1550615,4.5214762687683105,-22627416996.103504,1744061310.1550624,4.5214762687683105,0.0,1744061310.1550822,4.5214762687683105,28284271247.461903
+1744061310.174658,4.541447639465332,0.0724504764386385,1744061310.1746602,4.541447639465332,-0.02168427894635568,1744061310.174662,4.541447639465332,0.03228473117022809,1744061310.1746643,4.541447639465332,-56568542383.626076,1744061310.1746655,4.541447639465332,0.065,1744061310.1746666,4.541447639465332,3.141592653588261,1744061310.174668,4.541447639465332,0.08667603119737154,1744061310.1746688,4.541447639465332,1.2481348541503247e-22,1744061310.1746697,4.541447639465332,2.332521583134966,1744061310.1746712,4.541447639465332,0.0,1744061310.1746721,4.541447639465332,-22627416996.103504,1744061310.1746728,4.541447639465332,0.0,1744061310.174674,4.541447639465332,28284271247.461903
+1744061310.195019,4.561487674713135,0.0724504764386385,1744061310.195021,4.561487674713135,-0.02168427894635568,1744061310.1950228,4.561487674713135,0.03228473117022809,1744061310.195025,4.561487674713135,-56568542383.626076,1744061310.1950262,4.561487674713135,0.065,1744061310.1950274,4.561487674713135,3.141592653588261,1744061310.1950288,4.561487674713135,0.08667603119737154,1744061310.1950295,4.561487674713135,1.2481348541503247e-22,1744061310.1950305,4.561487674713135,2.332521583134966,1744061310.195032,4.561487674713135,0.0,1744061310.1950328,4.561487674713135,-22627416996.103504,1744061310.1950338,4.561487674713135,0.0,1744061310.1950347,4.561487674713135,28284271247.461903
+1744061310.214747,4.581488370895386,0.0724504764386385,1744061310.2147486,4.581488370895386,-0.02168427894635568,1744061310.2147508,4.581488370895386,0.03228473117022809,1744061310.2147524,4.581488370895386,-56568542383.626076,1744061310.2147539,4.581488370895386,0.065,1744061310.2147548,4.581488370895386,3.141592653588261,1744061310.2147558,4.581488370895386,0.08667603119737154,1744061310.214757,4.581488370895386,1.2481348541503247e-22,1744061310.214758,4.581488370895386,2.332521583134966,1744061310.2147593,4.581488370895386,0.0,1744061310.2147603,4.581488370895386,-22627416996.103504,1744061310.2147613,4.581488370895386,0.0,1744061310.2147622,4.581488370895386,28284271247.461903
+1744061310.2349179,4.601489782333374,0.0724504764386385,1744061310.2349198,4.601489782333374,-0.02168427894635568,1744061310.2349217,4.601489782333374,0.03228473117022809,1744061310.2349238,4.601489782333374,-56568542383.626076,1744061310.2349248,4.601489782333374,0.065,1744061310.234926,4.601489782333374,3.141592653588261,1744061310.2349272,4.601489782333374,0.08667603119737154,1744061310.234928,4.601489782333374,1.2481348541503247e-22,1744061310.2349288,4.601489782333374,2.332521583134966,1744061310.2349303,4.601489782333374,0.0,1744061310.234931,4.601489782333374,-22627416996.103504,1744061310.2349317,4.601489782333374,0.0,1744061310.2349327,4.601489782333374,28284271247.461903
+1744061310.2549167,4.621474504470825,0.0724504764386385,1744061310.2549188,4.621474504470825,-0.02168427894635568,1744061310.2549217,4.621474504470825,0.03228473117022809,1744061310.254924,4.621474504470825,-56568542383.626076,1744061310.2549257,4.621474504470825,0.065,1744061310.2549274,4.621474504470825,3.141592653588261,1744061310.254929,4.621474504470825,0.08667603119737154,1744061310.25493,4.621474504470825,1.2481348541503247e-22,1744061310.2549317,4.621474504470825,2.332521583134966,1744061310.2549345,4.621474504470825,0.0,1744061310.2549357,4.621474504470825,-22627416996.103504,1744061310.2549372,4.621474504470825,0.0,1744061310.2549388,4.621474504470825,28284271247.461903
+1744061310.274681,4.641455173492432,0.0724504764386385,1744061310.274683,4.641455173492432,-0.02168427894635568,1744061310.274685,4.641455173492432,0.03228473117022809,1744061310.274687,4.641455173492432,-56568542383.626076,1744061310.2746882,4.641455173492432,0.065,1744061310.2746894,4.641455173492432,3.141592653588261,1744061310.2746906,4.641455173492432,0.08667603119737154,1744061310.2746916,4.641455173492432,1.2481348541503247e-22,1744061310.2746923,4.641455173492432,2.332521583134966,1744061310.274694,4.641455173492432,0.0,1744061310.274695,4.641455173492432,-22627416996.103504,1744061310.2746959,4.641455173492432,0.0,1744061310.274697,4.641455173492432,28284271247.461903
+1744061310.2947094,4.66147780418396,0.0724504764386385,1744061310.2947114,4.66147780418396,-0.02168427894635568,1744061310.2947133,4.66147780418396,0.03228473117022809,1744061310.2947154,4.66147780418396,-56568542383.626076,1744061310.2947164,4.66147780418396,0.065,1744061310.294718,4.66147780418396,3.141592653588261,1744061310.294719,4.66147780418396,0.08667603119737154,1744061310.2947197,4.66147780418396,1.2481348541503247e-22,1744061310.2947206,4.66147780418396,2.332521583134966,1744061310.294722,4.66147780418396,0.0,1744061310.294723,4.66147780418396,-22627416996.103504,1744061310.294724,4.66147780418396,0.0,1744061310.2947252,4.66147780418396,28284271247.461903
+1744061310.314611,4.681412935256958,0.0724504764386385,1744061310.314613,4.681412935256958,-0.02168427894635568,1744061310.3146148,4.681412935256958,0.03228473117022809,1744061310.314617,4.681412935256958,-56568542383.626076,1744061310.314618,4.681412935256958,0.065,1744061310.31462,4.681412935256958,3.141592653588261,1744061310.314621,4.681412935256958,0.08667603119737154,1744061310.314622,4.681412935256958,1.2481348541503247e-22,1744061310.3146226,4.681412935256958,2.332521583134966,1744061310.3146243,4.681412935256958,0.0,1744061310.314625,4.681412935256958,-22627416996.103504,1744061310.314626,4.681412935256958,0.0,1744061310.3146272,4.681412935256958,28284271247.461903
+1744061310.3350391,4.701447248458862,0.06773717338949524,1744061310.3350415,4.701447248458862,-0.030316642092933856,1744061310.3350437,4.701447248458862,0.03220381077544095,1744061310.3350458,4.701447248458862,-56568542383.62599,1744061310.335047,4.701447248458862,0.065,1744061310.3350484,4.701447248458862,3.1415926535881082,1744061310.3350496,4.701447248458862,0.09531782007296744,1744061310.3350506,4.701447248458862,1.3725766144484942e-22,1744061310.3350518,4.701447248458862,2.316451469697183,1744061310.335053,4.701447248458862,0.0,1744061310.3350542,4.701447248458862,-22627416996.121185,1744061310.3350554,4.701447248458862,0.0,1744061310.3350563,4.701447248458862,28284271247.461903
+1744061310.3547058,4.7214515209198,0.06773717338949524,1744061310.354708,4.7214515209198,-0.030316642092933856,1744061310.35471,4.7214515209198,0.03220381077544095,1744061310.354712,4.7214515209198,-56568542383.62599,1744061310.3547132,4.7214515209198,0.065,1744061310.3547144,4.7214515209198,3.1415926535881082,1744061310.3547153,4.7214515209198,0.09531782007296744,1744061310.3547163,4.7214515209198,1.3725766144484942e-22,1744061310.3547175,4.7214515209198,2.316451469697183,1744061310.3547187,4.7214515209198,0.0,1744061310.3547196,4.7214515209198,-22627416996.116364,1744061310.3547208,4.7214515209198,0.0,1744061310.3547218,4.7214515209198,28284271247.461903
+1744061310.3747656,4.741448402404785,0.06773717338949524,1744061310.3747675,4.741448402404785,-0.030316642092933856,1744061310.3747697,4.741448402404785,0.03220381077544095,1744061310.374772,4.741448402404785,-56568542383.62599,1744061310.374773,4.741448402404785,0.065,1744061310.3747742,4.741448402404785,3.1415926535881082,1744061310.3747754,4.741448402404785,0.09531782007296744,1744061310.3747764,4.741448402404785,1.3725766144484942e-22,1744061310.374777,4.741448402404785,2.316451469697183,1744061310.374779,4.741448402404785,0.0,1744061310.3747797,4.741448402404785,-22627416996.116364,1744061310.374781,4.741448402404785,0.0,1744061310.3747818,4.741448402404785,28284271247.461903
+1744061310.3956048,4.761570692062378,0.06773717338949524,1744061310.395609,4.761570692062378,-0.030316642092933856,1744061310.3956118,4.761570692062378,0.03220381077544095,1744061310.3956141,4.761570692062378,-56568542383.62599,1744061310.3956158,4.761570692062378,0.065,1744061310.3956177,4.761570692062378,3.1415926535881082,1744061310.3956199,4.761570692062378,0.09531782007296744,1744061310.3956215,4.761570692062378,1.3725766144484942e-22,1744061310.3956234,4.761570692062378,2.316451469697183,1744061310.395625,4.761570692062378,0.0,1744061310.395627,4.761570692062378,-22627416996.116364,1744061310.3956282,4.761570692062378,0.0,1744061310.3956296,4.761570692062378,28284271247.461903
+1744061310.414748,4.7814836502075195,0.06773717338949524,1744061310.4147496,4.7814836502075195,-0.030316642092933856,1744061310.4147518,4.7814836502075195,0.03220381077544095,1744061310.4147537,4.7814836502075195,-56568542383.62599,1744061310.4147549,4.7814836502075195,0.065,1744061310.414756,4.7814836502075195,3.1415926535881082,1744061310.414757,4.7814836502075195,0.09531782007296744,1744061310.4147582,4.7814836502075195,1.3725766144484942e-22,1744061310.4147592,4.7814836502075195,2.316451469697183,1744061310.4147604,4.7814836502075195,0.0,1744061310.4147615,4.7814836502075195,-22627416996.116364,1744061310.4147625,4.7814836502075195,0.0,1744061310.4147635,4.7814836502075195,28284271247.461903
+1744061310.434967,4.801475524902344,0.06773717338949524,1744061310.434969,4.801475524902344,-0.030316642092933856,1744061310.434971,4.801475524902344,0.03220381077544095,1744061310.4349735,4.801475524902344,-56568542383.62599,1744061310.4349747,4.801475524902344,0.065,1744061310.4349766,4.801475524902344,3.1415926535881082,1744061310.4349775,4.801475524902344,0.09531782007296744,1744061310.4349785,4.801475524902344,1.3725766144484942e-22,1744061310.4349797,4.801475524902344,2.316451469697183,1744061310.4349813,4.801475524902344,0.0,1744061310.434982,4.801475524902344,-22627416996.116364,1744061310.4349835,4.801475524902344,0.0,1744061310.4349844,4.801475524902344,28284271247.461903
+1744061310.4547582,4.821450233459473,0.06773717338949524,1744061310.45476,4.821450233459473,-0.030316642092933856,1744061310.4547622,4.821450233459473,0.03220381077544095,1744061310.4547644,4.821450233459473,-56568542383.62599,1744061310.4547656,4.821450233459473,0.065,1744061310.4547665,4.821450233459473,3.1415926535881082,1744061310.454768,4.821450233459473,0.09531782007296744,1744061310.454769,4.821450233459473,1.3725766144484942e-22,1744061310.4547696,4.821450233459473,2.316451469697183,1744061310.4547713,4.821450233459473,0.0,1744061310.4547722,4.821450233459473,-22627416996.116364,1744061310.4547734,4.821450233459473,0.0,1744061310.4547746,4.821450233459473,28284271247.461903
+1744061310.474721,4.841451406478882,0.06773717338949524,1744061310.4747229,4.841451406478882,-0.030316642092933856,1744061310.474725,4.841451406478882,0.03220381077544095,1744061310.4747272,4.841451406478882,-56568542383.62599,1744061310.474728,4.841451406478882,0.065,1744061310.4747295,4.841451406478882,3.1415926535881082,1744061310.4747305,4.841451406478882,0.09531782007296744,1744061310.4747314,4.841451406478882,1.3725766144484942e-22,1744061310.4747326,4.841451406478882,2.316451469697183,1744061310.4747336,4.841451406478882,0.0,1744061310.4747345,4.841451406478882,-22627416996.116364,1744061310.4747355,4.841451406478882,0.0,1744061310.4747367,4.841451406478882,28284271247.461903
+1744061310.4947803,4.861456632614136,0.06773717338949524,1744061310.4947822,4.861456632614136,-0.030316642092933856,1744061310.4947846,4.861456632614136,0.03220381077544095,1744061310.4947865,4.861456632614136,-56568542383.62599,1744061310.4947877,4.861456632614136,0.065,1744061310.494789,4.861456632614136,3.1415926535881082,1744061310.4947898,4.861456632614136,0.09531782007296744,1744061310.494791,4.861456632614136,1.3725766144484942e-22,1744061310.494792,4.861456632614136,2.316451469697183,1744061310.4947932,4.861456632614136,0.0,1744061310.4947941,4.861456632614136,-22627416996.116364,1744061310.4947956,4.861456632614136,0.0,1744061310.4947965,4.861456632614136,28284271247.461903
+1744061310.5146465,4.88147234916687,0.06773717338949524,1744061310.514648,4.88147234916687,-0.030316642092933856,1744061310.5146503,4.88147234916687,0.03220381077544095,1744061310.5146523,4.88147234916687,-56568542383.62599,1744061310.5146532,4.88147234916687,0.065,1744061310.5146544,4.88147234916687,3.1415926535881082,1744061310.5146558,4.88147234916687,0.09531782007296744,1744061310.5146565,4.88147234916687,1.3725766144484942e-22,1744061310.5146575,4.88147234916687,2.316451469697183,1744061310.514659,4.88147234916687,0.0,1744061310.51466,4.88147234916687,-22627416996.116364,1744061310.5146608,4.88147234916687,0.0,1744061310.5146618,4.88147234916687,28284271247.461903
+1744061310.5349643,4.901495695114136,0.06773717338949524,1744061310.5349662,4.901495695114136,-0.030316642092933856,1744061310.5349684,4.901495695114136,0.03220381077544095,1744061310.53497,4.901495695114136,-56568542383.62599,1744061310.5349715,4.901495695114136,0.065,1744061310.5349727,4.901495695114136,3.1415926535881082,1744061310.5349736,4.901495695114136,0.09531782007296744,1744061310.5349746,4.901495695114136,1.3725766144484942e-22,1744061310.5349755,4.901495695114136,2.316451469697183,1744061310.5349767,4.901495695114136,0.0,1744061310.5349774,4.901495695114136,-22627416996.116364,1744061310.5349786,4.901495695114136,0.0,1744061310.5349796,4.901495695114136,28284271247.461903
+1744061310.5547678,4.921473026275635,0.06773717338949524,1744061310.5547698,4.921473026275635,-0.030316642092933856,1744061310.5547717,4.921473026275635,0.03220381077544095,1744061310.5547738,4.921473026275635,-56568542383.62599,1744061310.5547748,4.921473026275635,0.065,1744061310.554776,4.921473026275635,3.1415926535881082,1744061310.5547771,4.921473026275635,0.09531782007296744,1744061310.554778,4.921473026275635,1.3725766144484942e-22,1744061310.5547788,4.921473026275635,2.316451469697183,1744061310.5547805,4.921473026275635,0.0,1744061310.5547814,4.921473026275635,-22627416996.116364,1744061310.5547829,4.921473026275635,0.0,1744061310.5547838,4.921473026275635,28284271247.461903
+1744061310.574728,4.941452980041504,0.06773717338949524,1744061310.57473,4.941452980041504,-0.030316642092933856,1744061310.5747323,4.941452980041504,0.03220381077544095,1744061310.5747344,4.941452980041504,-56568542383.62599,1744061310.5747356,4.941452980041504,0.065,1744061310.5747368,4.941452980041504,3.1415926535881082,1744061310.574738,4.941452980041504,0.09531782007296744,1744061310.5747387,4.941452980041504,1.3725766144484942e-22,1744061310.5747397,4.941452980041504,2.316451469697183,1744061310.574741,4.941452980041504,0.0,1744061310.574742,4.941452980041504,-22627416996.116364,1744061310.574743,4.941452980041504,0.0,1744061310.574744,4.941452980041504,28284271247.461903
+1744061310.5946827,4.9614574909210205,0.06773717338949524,1744061310.5946844,4.9614574909210205,-0.030316642092933856,1744061310.5946867,4.9614574909210205,0.03220381077544095,1744061310.5946887,4.9614574909210205,-56568542383.62599,1744061310.5946898,4.9614574909210205,0.065,1744061310.594691,4.9614574909210205,3.1415926535881082,1744061310.594692,4.9614574909210205,0.09531782007296744,1744061310.594693,4.9614574909210205,1.3725766144484942e-22,1744061310.594694,4.9614574909210205,2.316451469697183,1744061310.5946953,4.9614574909210205,0.0,1744061310.5946965,4.9614574909210205,-22627416996.116364,1744061310.5946977,4.9614574909210205,0.0,1744061310.5946984,4.9614574909210205,28284271247.461903
+1744061310.6146555,4.9814772605896,0.06773717338949524,1744061310.6146572,4.9814772605896,-0.030316642092933856,1744061310.6146593,4.9814772605896,0.03220381077544095,1744061310.6146612,4.9814772605896,-56568542383.62599,1744061310.6146624,4.9814772605896,0.065,1744061310.6146636,4.9814772605896,3.1415926535881082,1744061310.614665,4.9814772605896,0.09531782007296744,1744061310.6146657,4.9814772605896,1.3725766144484942e-22,1744061310.6146667,4.9814772605896,2.316451469697183,1744061310.6146684,4.9814772605896,0.0,1744061310.6146693,4.9814772605896,-22627416996.116364,1744061310.6146703,4.9814772605896,0.0,1744061310.6146715,4.9814772605896,28284271247.461903
+1744061310.6349704,5.001452922821045,0.06773717338949524,1744061310.634972,5.001452922821045,-0.030316642092933856,1744061310.6349742,5.001452922821045,0.03220381077544095,1744061310.6349761,5.001452922821045,-56568542383.62599,1744061310.6349773,5.001452922821045,0.065,1744061310.6349785,5.001452922821045,3.1415926535881082,1744061310.6349797,5.001452922821045,0.09531782007296744,1744061310.6349807,5.001452922821045,1.3725766144484942e-22,1744061310.6349816,5.001452922821045,2.316451469697183,1744061310.6349826,5.001452922821045,0.0,1744061310.6349838,5.001452922821045,-22627416996.116364,1744061310.6349847,5.001452922821045,0.0,1744061310.6349857,5.001452922821045,28284271247.461903
+1744061310.6548543,5.021479606628418,0.06773717338949524,1744061310.6548562,5.021479606628418,-0.030316642092933856,1744061310.6548586,5.021479606628418,0.03220381077544095,1744061310.6548605,5.021479606628418,-56568542383.62599,1744061310.6548615,5.021479606628418,0.065,1744061310.654863,5.021479606628418,3.1415926535881082,1744061310.654864,5.021479606628418,0.09531782007296744,1744061310.6548653,5.021479606628418,1.3725766144484942e-22,1744061310.654866,5.021479606628418,2.316451469697183,1744061310.6548674,5.021479606628418,0.0,1744061310.6548684,5.021479606628418,-22627416996.116364,1744061310.6548698,5.021479606628418,0.0,1744061310.6548705,5.021479606628418,28284271247.461903
+1744061310.674696,5.0414509773254395,0.06773717338949524,1744061310.674699,5.0414509773254395,-0.030316642092933856,1744061310.6747022,5.0414509773254395,0.03220381077544095,1744061310.6747043,5.0414509773254395,-56568542383.62599,1744061310.6747057,5.0414509773254395,0.065,1744061310.6747077,5.0414509773254395,3.1415926535881082,1744061310.674709,5.0414509773254395,0.09531782007296744,1744061310.6747098,5.0414509773254395,1.3725766144484942e-22,1744061310.6747112,5.0414509773254395,2.316451469697183,1744061310.6747136,5.0414509773254395,0.0,1744061310.6747146,5.0414509773254395,-22627416996.116364,1744061310.674716,5.0414509773254395,0.0,1744061310.6747174,5.0414509773254395,28284271247.461903
+1744061310.6948807,5.061461925506592,0.06773717338949524,1744061310.6948826,5.061461925506592,-0.030316642092933856,1744061310.6948845,5.061461925506592,0.03220381077544095,1744061310.6948867,5.061461925506592,-56568542383.62599,1744061310.6948879,5.061461925506592,0.065,1744061310.6948893,5.061461925506592,3.1415926535881082,1744061310.6948905,5.061461925506592,0.09531782007296744,1744061310.6948912,5.061461925506592,1.3725766144484942e-22,1744061310.6948924,5.061461925506592,2.316451469697183,1744061310.6948936,5.061461925506592,0.0,1744061310.6948946,5.061461925506592,-22627416996.116364,1744061310.6948955,5.061461925506592,0.0,1744061310.6948965,5.061461925506592,28284271247.461903
+1744061310.7146165,5.081446886062622,0.06773717338949524,1744061310.7146184,5.081446886062622,-0.030316642092933856,1744061310.7146204,5.081446886062622,0.03220381077544095,1744061310.7146223,5.081446886062622,-56568542383.62599,1744061310.7146232,5.081446886062622,0.065,1744061310.7146244,5.081446886062622,3.1415926535881082,1744061310.7146256,5.081446886062622,0.09531782007296744,1744061310.7146266,5.081446886062622,1.3725766144484942e-22,1744061310.7146273,5.081446886062622,2.316451469697183,1744061310.7146287,5.081446886062622,0.0,1744061310.7146297,5.081446886062622,-22627416996.116364,1744061310.7146306,5.081446886062622,0.0,1744061310.7146318,5.081446886062622,28284271247.461903
+1744061310.7350144,5.101477861404419,0.06773717338949524,1744061310.735016,5.101477861404419,-0.030316642092933856,1744061310.7350183,5.101477861404419,0.03220381077544095,1744061310.7350206,5.101477861404419,-56568542383.62599,1744061310.7350218,5.101477861404419,0.065,1744061310.7350228,5.101477861404419,3.1415926535881082,1744061310.7350242,5.101477861404419,0.09531782007296744,1744061310.735025,5.101477861404419,1.3725766144484942e-22,1744061310.735026,5.101477861404419,2.316451469697183,1744061310.7350273,5.101477861404419,0.0,1744061310.7350283,5.101477861404419,-22627416996.116364,1744061310.7350292,5.101477861404419,0.0,1744061310.7350302,5.101477861404419,28284271247.461903
+1744061310.754911,5.121451377868652,0.06773717338949524,1744061310.7549133,5.121451377868652,-0.030316642092933856,1744061310.754916,5.121451377868652,0.03220381077544095,1744061310.7549179,5.121451377868652,-56568542383.62599,1744061310.754919,5.121451377868652,0.065,1744061310.7549205,5.121451377868652,3.1415926535881082,1744061310.7549214,5.121451377868652,0.09531782007296744,1744061310.7549222,5.121451377868652,1.3725766144484942e-22,1744061310.7549236,5.121451377868652,2.316451469697183,1744061310.754925,5.121451377868652,0.0,1744061310.754926,5.121451377868652,-22627416996.116364,1744061310.7549274,5.121451377868652,0.0,1744061310.7549286,5.121451377868652,28284271247.461903
+1744061310.7746437,5.141446352005005,0.06773717338949524,1744061310.7746456,5.141446352005005,-0.030316642092933856,1744061310.7746477,5.141446352005005,0.03220381077544095,1744061310.7746499,5.141446352005005,-56568542383.62599,1744061310.7746508,5.141446352005005,0.065,1744061310.7746522,5.141446352005005,3.1415926535881082,1744061310.7746532,5.141446352005005,0.09531782007296744,1744061310.7746542,5.141446352005005,1.3725766144484942e-22,1744061310.7746553,5.141446352005005,2.316451469697183,1744061310.7746565,5.141446352005005,0.0,1744061310.7746575,5.141446352005005,-22627416996.116364,1744061310.7746582,5.141446352005005,0.0,1744061310.7746594,5.141446352005005,28284271247.461903
+1744061310.7947583,5.161448001861572,0.06773717338949524,1744061310.7947602,5.161448001861572,-0.030316642092933856,1744061310.7947621,5.161448001861572,0.03220381077544095,1744061310.7947643,5.161448001861572,-56568542383.62599,1744061310.7947655,5.161448001861572,0.065,1744061310.794767,5.161448001861572,3.1415926535881082,1744061310.7947679,5.161448001861572,0.09531782007296744,1744061310.7947686,5.161448001861572,1.3725766144484942e-22,1744061310.7947698,5.161448001861572,2.316451469697183,1744061310.794771,5.161448001861572,0.0,1744061310.794772,5.161448001861572,-22627416996.116364,1744061310.794773,5.161448001861572,0.0,1744061310.794774,5.161448001861572,28284271247.461903
+1744061310.8146694,5.181471347808838,0.06773717338949524,1744061310.814671,5.181471347808838,-0.030316642092933856,1744061310.8146732,5.181471347808838,0.03220381077544095,1744061310.814675,5.181471347808838,-56568542383.62599,1744061310.8146763,5.181471347808838,0.065,1744061310.8146775,5.181471347808838,3.1415926535881082,1744061310.8146784,5.181471347808838,0.09531782007296744,1744061310.8146796,5.181471347808838,1.3725766144484942e-22,1744061310.8146803,5.181471347808838,2.316451469697183,1744061310.8146818,5.181471347808838,0.0,1744061310.8146827,5.181471347808838,-22627416996.116364,1744061310.8146837,5.181471347808838,0.0,1744061310.8146846,5.181471347808838,28284271247.461903
+1744061310.8349364,5.201480388641357,0.0625301977626323,1744061310.8349378,5.201480388641357,-0.03866320917876114,1744061310.83494,5.201480388641357,0.0033437784651684935,1744061310.8349419,5.201480388641357,-56568542383.59713,1744061310.834943,5.201480388641357,0.065,1744061310.8349442,5.201480388641357,3.141592653587961,1744061310.8349452,5.201480388641357,0.10365815119703371,1744061310.8349464,5.201480388641357,1.492677383109152e-22,1744061310.8349473,5.201480388641357,2.3010469405642406,1744061310.8349485,5.201480388641357,0.0,1744061310.8349495,5.201480388641357,-22627416996.13331,1744061310.8349504,5.201480388641357,0.0,1744061310.8349514,5.201480388641357,28284271247.461903
+1744061310.8553395,5.221482515335083,0.0625301977626323,1744061310.8553462,5.221482515335083,-0.03866320917876114,1744061310.85535,5.221482515335083,0.0033437784651684935,1744061310.8553524,5.221482515335083,-56568542383.59713,1744061310.8553536,5.221482515335083,0.065,1744061310.855356,5.221482515335083,3.141592653587961,1744061310.8553574,5.221482515335083,0.10365815119703371,1744061310.8553588,5.221482515335083,1.492677383109152e-22,1744061310.85536,5.221482515335083,2.3010469405642406,1744061310.8553627,5.221482515335083,0.0,1744061310.8553636,5.221482515335083,-22627416996.128685,1744061310.855365,5.221482515335083,0.0,1744061310.8553662,5.221482515335083,28284271247.461903
+1744061310.874594,5.2414469718933105,0.0625301977626323,1744061310.8745959,5.2414469718933105,-0.03866320917876114,1744061310.8745978,5.2414469718933105,0.0033437784651684935,1744061310.8746,5.2414469718933105,-56568542383.59713,1744061310.874601,5.2414469718933105,0.065,1744061310.8746023,5.2414469718933105,3.141592653587961,1744061310.8746033,5.2414469718933105,0.10365815119703371,1744061310.8746042,5.2414469718933105,1.492677383109152e-22,1744061310.8746054,5.2414469718933105,2.3010469405642406,1744061310.8746066,5.2414469718933105,0.0,1744061310.8746076,5.2414469718933105,-22627416996.128685,1744061310.874609,5.2414469718933105,0.0,1744061310.8746097,5.2414469718933105,28284271247.461903
+1744061310.8947213,5.261490106582642,0.0625301977626323,1744061310.8947232,5.261490106582642,-0.03866320917876114,1744061310.8947253,5.261490106582642,0.0033437784651684935,1744061310.8947272,5.261490106582642,-56568542383.59713,1744061310.8947284,5.261490106582642,0.065,1744061310.8947296,5.261490106582642,3.141592653587961,1744061310.8947308,5.261490106582642,0.10365815119703371,1744061310.8947315,5.261490106582642,1.492677383109152e-22,1744061310.8947325,5.261490106582642,2.3010469405642406,1744061310.894734,5.261490106582642,0.0,1744061310.8947349,5.261490106582642,-22627416996.128685,1744061310.894736,5.261490106582642,0.0,1744061310.894737,5.261490106582642,28284271247.461903
+1744061310.9147317,5.281492233276367,0.0625301977626323,1744061310.9147336,5.281492233276367,-0.03866320917876114,1744061310.9147356,5.281492233276367,0.0033437784651684935,1744061310.9147377,5.281492233276367,-56568542383.59713,1744061310.914739,5.281492233276367,0.065,1744061310.9147403,5.281492233276367,3.141592653587961,1744061310.9147415,5.281492233276367,0.10365815119703371,1744061310.9147422,5.281492233276367,1.492677383109152e-22,1744061310.9147432,5.281492233276367,2.3010469405642406,1744061310.9147446,5.281492233276367,0.0,1744061310.9147456,5.281492233276367,-22627416996.128685,1744061310.9147465,5.281492233276367,0.0,1744061310.9147475,5.281492233276367,28284271247.461903
+1744061310.9358473,5.301445484161377,0.0625301977626323,1744061310.9358513,5.301445484161377,-0.03866320917876114,1744061310.9358556,5.301445484161377,0.0033437784651684935,1744061310.9358602,5.301445484161377,-56568542383.59713,1744061310.9358625,5.301445484161377,0.065,1744061310.9358656,5.301445484161377,3.141592653587961,1744061310.9358685,5.301445484161377,0.10365815119703371,1744061310.935871,5.301445484161377,1.492677383109152e-22,1744061310.935874,5.301445484161377,2.3010469405642406,1744061310.935877,5.301445484161377,0.0,1744061310.9358797,5.301445484161377,-22627416996.128685,1744061310.9358826,5.301445484161377,0.0,1744061310.9358854,5.301445484161377,28284271247.461903
+1744061310.9550357,5.321471929550171,0.0625301977626323,1744061310.9550374,5.321471929550171,-0.03866320917876114,1744061310.9550402,5.321471929550171,0.0033437784651684935,1744061310.9550424,5.321471929550171,-56568542383.59713,1744061310.9550436,5.321471929550171,0.065,1744061310.9550452,5.321471929550171,3.141592653587961,1744061310.9550464,5.321471929550171,0.10365815119703371,1744061310.9550474,5.321471929550171,1.492677383109152e-22,1744061310.9550486,5.321471929550171,2.3010469405642406,1744061310.9550502,5.321471929550171,0.0,1744061310.955051,5.321471929550171,-22627416996.128685,1744061310.9550524,5.321471929550171,0.0,1744061310.9550533,5.321471929550171,28284271247.461903
+1744061310.9746585,5.341446399688721,0.0625301977626323,1744061310.9746604,5.341446399688721,-0.03866320917876114,1744061310.9746623,5.341446399688721,0.0033437784651684935,1744061310.9746644,5.341446399688721,-56568542383.59713,1744061310.9746654,5.341446399688721,0.065,1744061310.9746668,5.341446399688721,3.141592653587961,1744061310.9746678,5.341446399688721,0.10365815119703371,1744061310.9746687,5.341446399688721,1.492677383109152e-22,1744061310.9746695,5.341446399688721,2.3010469405642406,1744061310.974671,5.341446399688721,0.0,1744061310.9746718,5.341446399688721,-22627416996.128685,1744061310.9746728,5.341446399688721,0.0,1744061310.974674,5.341446399688721,28284271247.461903
+1744061310.9946957,5.361480236053467,0.0625301977626323,1744061310.9946976,5.361480236053467,-0.03866320917876114,1744061310.9946995,5.361480236053467,0.0033437784651684935,1744061310.9947016,5.361480236053467,-56568542383.59713,1744061310.9947026,5.361480236053467,0.065,1744061310.9947038,5.361480236053467,3.141592653587961,1744061310.994705,5.361480236053467,0.10365815119703371,1744061310.994706,5.361480236053467,1.492677383109152e-22,1744061310.9947066,5.361480236053467,2.3010469405642406,1744061310.9947083,5.361480236053467,0.0,1744061310.9947093,5.361480236053467,-22627416996.128685,1744061310.99471,5.361480236053467,0.0,1744061310.994711,5.361480236053467,28284271247.461903
+1744061311.0146952,5.381453514099121,0.0625301977626323,1744061311.014697,5.381453514099121,-0.03866320917876114,1744061311.014699,5.381453514099121,0.0033437784651684935,1744061311.0147011,5.381453514099121,-56568542383.59713,1744061311.014702,5.381453514099121,0.065,1744061311.0147033,5.381453514099121,3.141592653587961,1744061311.0147047,5.381453514099121,0.10365815119703371,1744061311.0147054,5.381453514099121,1.492677383109152e-22,1744061311.0147064,5.381453514099121,2.3010469405642406,1744061311.0147078,5.381453514099121,0.0,1744061311.0147088,5.381453514099121,-22627416996.128685,1744061311.0147097,5.381453514099121,0.0,1744061311.014711,5.381453514099121,28284271247.461903
+1744061311.0348535,5.401444911956787,0.0625301977626323,1744061311.0348551,5.401444911956787,-0.03866320917876114,1744061311.0348573,5.401444911956787,0.0033437784651684935,1744061311.0348594,5.401444911956787,-56568542383.59713,1744061311.0348606,5.401444911956787,0.065,1744061311.0348618,5.401444911956787,3.141592653587961,1744061311.0348628,5.401444911956787,0.10365815119703371,1744061311.0348637,5.401444911956787,1.492677383109152e-22,1744061311.0348647,5.401444911956787,2.3010469405642406,1744061311.0348659,5.401444911956787,0.0,1744061311.0348666,5.401444911956787,-22627416996.128685,1744061311.034868,5.401444911956787,0.0,1744061311.0348687,5.401444911956787,28284271247.461903
+1744061311.055305,5.421535491943359,0.0625301977626323,1744061311.0553071,5.421535491943359,-0.03866320917876114,1744061311.05531,5.421535491943359,0.0033437784651684935,1744061311.0553124,5.421535491943359,-56568542383.59713,1744061311.0553133,5.421535491943359,0.065,1744061311.055315,5.421535491943359,3.141592653587961,1744061311.0553164,5.421535491943359,0.10365815119703371,1744061311.0553174,5.421535491943359,1.492677383109152e-22,1744061311.0553188,5.421535491943359,2.3010469405642406,1744061311.0553207,5.421535491943359,0.0,1744061311.055322,5.421535491943359,-22627416996.128685,1744061311.0553231,5.421535491943359,0.0,1744061311.0553238,5.421535491943359,28284271247.461903
+1744061311.074724,5.441488981246948,0.0625301977626323,1744061311.0747259,5.441488981246948,-0.03866320917876114,1744061311.0747283,5.441488981246948,0.0033437784651684935,1744061311.0747302,5.441488981246948,-56568542383.59713,1744061311.0747313,5.441488981246948,0.065,1744061311.0747328,5.441488981246948,3.141592653587961,1744061311.074734,5.441488981246948,0.10365815119703371,1744061311.0747352,5.441488981246948,1.492677383109152e-22,1744061311.074736,5.441488981246948,2.3010469405642406,1744061311.0747375,5.441488981246948,0.0,1744061311.0747385,5.441488981246948,-22627416996.128685,1744061311.0747395,5.441488981246948,0.0,1744061311.0747404,5.441488981246948,28284271247.461903
+1744061311.0946808,5.4614503383636475,0.0625301977626323,1744061311.0946827,5.4614503383636475,-0.03866320917876114,1744061311.0946846,5.4614503383636475,0.0033437784651684935,1744061311.0946867,5.4614503383636475,-56568542383.59713,1744061311.094688,5.4614503383636475,0.065,1744061311.0946894,5.4614503383636475,3.141592653587961,1744061311.0946903,5.4614503383636475,0.10365815119703371,1744061311.094691,5.4614503383636475,1.492677383109152e-22,1744061311.094692,5.4614503383636475,2.3010469405642406,1744061311.0946934,5.4614503383636475,0.0,1744061311.0946944,5.4614503383636475,-22627416996.128685,1744061311.0946953,5.4614503383636475,0.0,1744061311.0946965,5.4614503383636475,28284271247.461903
+1744061311.11468,5.481447219848633,0.0625301977626323,1744061311.1146824,5.481447219848633,-0.03866320917876114,1744061311.1146855,5.481447219848633,0.0033437784651684935,1744061311.1146877,5.481447219848633,-56568542383.59713,1744061311.1146898,5.481447219848633,0.065,1744061311.114691,5.481447219848633,3.141592653587961,1744061311.1146927,5.481447219848633,0.10365815119703371,1744061311.114694,5.481447219848633,1.492677383109152e-22,1744061311.114695,5.481447219848633,2.3010469405642406,1744061311.114697,5.481447219848633,0.0,1744061311.1146984,5.481447219848633,-22627416996.128685,1744061311.1146998,5.481447219848633,0.0,1744061311.1147013,5.481447219848633,28284271247.461903
+1744061311.135003,5.501474857330322,0.0625301977626323,1744061311.1350052,5.501474857330322,-0.03866320917876114,1744061311.1350071,5.501474857330322,0.0033437784651684935,1744061311.1350093,5.501474857330322,-56568542383.59713,1744061311.1350102,5.501474857330322,0.065,1744061311.1350114,5.501474857330322,3.141592653587961,1744061311.1350124,5.501474857330322,0.10365815119703371,1744061311.1350133,5.501474857330322,1.492677383109152e-22,1744061311.135014,5.501474857330322,2.3010469405642406,1744061311.1350155,5.501474857330322,0.0,1744061311.1350162,5.501474857330322,-22627416996.128685,1744061311.1350174,5.501474857330322,0.0,1744061311.1350183,5.501474857330322,28284271247.461903
+1744061311.155,5.521489858627319,0.0625301977626323,1744061311.155002,5.521489858627319,-0.03866320917876114,1744061311.1550047,5.521489858627319,0.0033437784651684935,1744061311.1550066,5.521489858627319,-56568542383.59713,1744061311.1550078,5.521489858627319,0.065,1744061311.1550093,5.521489858627319,3.141592653587961,1744061311.1550105,5.521489858627319,0.10365815119703371,1744061311.1550114,5.521489858627319,1.492677383109152e-22,1744061311.1550128,5.521489858627319,2.3010469405642406,1744061311.155014,5.521489858627319,0.0,1744061311.1550152,5.521489858627319,-22627416996.128685,1744061311.1550164,5.521489858627319,0.0,1744061311.1550174,5.521489858627319,28284271247.461903
+1744061311.1747708,5.541469097137451,0.0625301977626323,1744061311.174773,5.541469097137451,-0.03866320917876114,1744061311.1747758,5.541469097137451,0.0033437784651684935,1744061311.1747777,5.541469097137451,-56568542383.59713,1744061311.174779,5.541469097137451,0.065,1744061311.1747801,5.541469097137451,3.141592653587961,1744061311.1747818,5.541469097137451,0.10365815119703371,1744061311.1747825,5.541469097137451,1.492677383109152e-22,1744061311.1747835,5.541469097137451,2.3010469405642406,1744061311.1747847,5.541469097137451,0.0,1744061311.174786,5.541469097137451,-22627416996.128685,1744061311.174787,5.541469097137451,0.0,1744061311.174788,5.541469097137451,28284271247.461903
+1744061311.1949418,5.561470985412598,0.0625301977626323,1744061311.1949434,5.561470985412598,-0.03866320917876114,1744061311.1949456,5.561470985412598,0.0033437784651684935,1744061311.1949475,5.561470985412598,-56568542383.59713,1744061311.194949,5.561470985412598,0.065,1744061311.19495,5.561470985412598,3.141592653587961,1744061311.1949515,5.561470985412598,0.10365815119703371,1744061311.1949522,5.561470985412598,1.492677383109152e-22,1744061311.1949534,5.561470985412598,2.3010469405642406,1744061311.194955,5.561470985412598,0.0,1744061311.1949558,5.561470985412598,-22627416996.128685,1744061311.1949568,5.561470985412598,0.0,1744061311.1949577,5.561470985412598,28284271247.461903
+1744061311.215401,5.581509590148926,0.0625301977626323,1744061311.2154036,5.581509590148926,-0.03866320917876114,1744061311.2154062,5.581509590148926,0.0033437784651684935,1744061311.215408,5.581509590148926,-56568542383.59713,1744061311.2154098,5.581509590148926,0.065,1744061311.2154114,5.581509590148926,3.141592653587961,1744061311.2154133,5.581509590148926,0.10365815119703371,1744061311.2154338,5.581509590148926,1.492677383109152e-22,1744061311.2154353,5.581509590148926,2.3010469405642406,1744061311.2154384,5.581509590148926,0.0,1744061311.2154396,5.581509590148926,-22627416996.128685,1744061311.215441,5.581509590148926,0.0,1744061311.2154427,5.581509590148926,28284271247.461903
+1744061311.2349153,5.601451635360718,0.0625301977626323,1744061311.2349172,5.601451635360718,-0.03866320917876114,1744061311.2349198,5.601451635360718,0.0033437784651684935,1744061311.2349217,5.601451635360718,-56568542383.59713,1744061311.2349231,5.601451635360718,0.065,1744061311.2349243,5.601451635360718,3.141592653587961,1744061311.2349257,5.601451635360718,0.10365815119703371,1744061311.2349267,5.601451635360718,1.492677383109152e-22,1744061311.234928,5.601451635360718,2.3010469405642406,1744061311.234929,5.601451635360718,0.0,1744061311.2349303,5.601451635360718,-22627416996.128685,1744061311.2349315,5.601451635360718,0.0,1744061311.2349324,5.601451635360718,28284271247.461903
+1744061311.2550137,5.621497392654419,0.0625301977626323,1744061311.2550166,5.621497392654419,-0.03866320917876114,1744061311.255019,5.621497392654419,0.0033437784651684935,1744061311.255021,5.621497392654419,-56568542383.59713,1744061311.2550223,5.621497392654419,0.065,1744061311.2550237,5.621497392654419,3.141592653587961,1744061311.2550247,5.621497392654419,0.10365815119703371,1744061311.2550259,5.621497392654419,1.492677383109152e-22,1744061311.2550273,5.621497392654419,2.3010469405642406,1744061311.2550292,5.621497392654419,0.0,1744061311.2550302,5.621497392654419,-22627416996.128685,1744061311.2550316,5.621497392654419,0.0,1744061311.2550325,5.621497392654419,28284271247.461903
+1744061311.274721,5.641483783721924,0.0625301977626323,1744061311.274723,5.641483783721924,-0.03866320917876114,1744061311.2747252,5.641483783721924,0.0033437784651684935,1744061311.2747273,5.641483783721924,-56568542383.59713,1744061311.2747288,5.641483783721924,0.065,1744061311.27473,5.641483783721924,3.141592653587961,1744061311.274731,5.641483783721924,0.10365815119703371,1744061311.274732,5.641483783721924,1.492677383109152e-22,1744061311.274733,5.641483783721924,2.3010469405642406,1744061311.2747345,5.641483783721924,0.0,1744061311.2747355,5.641483783721924,-22627416996.128685,1744061311.2747366,5.641483783721924,0.0,1744061311.2747376,5.641483783721924,28284271247.461903
+1744061311.294647,5.661444664001465,0.0625301977626323,1744061311.2946491,5.661444664001465,-0.03866320917876114,1744061311.2946515,5.661444664001465,0.0033437784651684935,1744061311.294654,5.661444664001465,-56568542383.59713,1744061311.294655,5.661444664001465,0.065,1744061311.2946568,5.661444664001465,3.141592653587961,1744061311.2946577,5.661444664001465,0.10365815119703371,1744061311.294659,5.661444664001465,1.492677383109152e-22,1744061311.2946599,5.661444664001465,2.3010469405642406,1744061311.294661,5.661444664001465,0.0,1744061311.2946625,5.661444664001465,-22627416996.128685,1744061311.2946634,5.661444664001465,0.0,1744061311.2946644,5.661444664001465,28284271247.461903
+1744061311.314756,5.681488990783691,0.0625301977626323,1744061311.3147576,5.681488990783691,-0.03866320917876114,1744061311.3147597,5.681488990783691,0.0033437784651684935,1744061311.3147616,5.681488990783691,-56568542383.59713,1744061311.314763,5.681488990783691,0.065,1744061311.3147643,5.681488990783691,3.141592653587961,1744061311.3147652,5.681488990783691,0.10365815119703371,1744061311.3147662,5.681488990783691,1.492677383109152e-22,1744061311.3147671,5.681488990783691,2.3010469405642406,1744061311.3147683,5.681488990783691,0.0,1744061311.3147697,5.681488990783691,-22627416996.128685,1744061311.3147707,5.681488990783691,0.0,1744061311.3147714,5.681488990783691,28284271247.461903
+1744061311.335062,5.701495885848999,0.057568652950039975,1744061311.3350637,5.701495885848999,-0.04252348721638441,1744061311.3350658,5.701495885848999,0.0033068568065808684,1744061311.335068,5.701495885848999,-56568542383.59709,1744061311.3350692,5.701495885848999,0.065,1744061311.3350701,5.701495885848999,3.1415926535878924,1744061311.3350716,5.701495885848999,0.1075268590076117,1744061311.3350723,5.701495885848999,1.5483867758008976e-22,1744061311.3350735,5.701495885848999,2.2939362872390587,1744061311.335075,5.701495885848999,0.0,1744061311.3350759,5.701495885848999,-22627416996.1365,1744061311.3350768,5.701495885848999,0.0,1744061311.3350775,5.701495885848999,28284271247.461903
+1744061311.3548486,5.721494436264038,0.057568652950039975,1744061311.3548505,5.721494436264038,-0.04252348721638441,1744061311.3548534,5.721494436264038,0.0033068568065808684,1744061311.3548555,5.721494436264038,-56568542383.59709,1744061311.3548567,5.721494436264038,0.065,1744061311.3548741,5.721494436264038,3.1415926535878924,1744061311.3548756,5.721494436264038,0.1075268590076117,1744061311.3548765,5.721494436264038,1.5483867758008976e-22,1744061311.3548777,5.721494436264038,2.2939362872390587,1744061311.3548794,5.721494436264038,0.0,1744061311.3548806,5.721494436264038,-22627416996.134373,1744061311.3548815,5.721494436264038,0.0,1744061311.3548825,5.721494436264038,28284271247.461903
+1744061311.3747387,5.741481781005859,0.057568652950039975,1744061311.3747404,5.741481781005859,-0.04252348721638441,1744061311.374759,5.741481781005859,0.0033068568065808684,1744061311.374761,5.741481781005859,-56568542383.59709,1744061311.3747623,5.741481781005859,0.065,1744061311.3747637,5.741481781005859,3.1415926535878924,1744061311.3747647,5.741481781005859,0.1075268590076117,1744061311.3747659,5.741481781005859,1.5483867758008976e-22,1744061311.3747666,5.741481781005859,2.2939362872390587,1744061311.3747685,5.741481781005859,0.0,1744061311.3747694,5.741481781005859,-22627416996.134373,1744061311.3747704,5.741481781005859,0.0,1744061311.3747714,5.741481781005859,28284271247.461903
+1744061311.3954697,5.76151180267334,0.057568652950039975,1744061311.3954725,5.76151180267334,-0.04252348721638441,1744061311.3954751,5.76151180267334,0.0033068568065808684,1744061311.3954773,5.76151180267334,-56568542383.59709,1744061311.3954785,5.76151180267334,0.065,1744061311.3954806,5.76151180267334,3.1415926535878924,1744061311.3955,5.76151180267334,0.1075268590076117,1744061311.395501,5.76151180267334,1.5483867758008976e-22,1744061311.3955019,5.76151180267334,2.2939362872390587,1744061311.3955038,5.76151180267334,0.0,1744061311.3955057,5.76151180267334,-22627416996.134373,1744061311.3955069,5.76151180267334,0.0,1744061311.395508,5.76151180267334,28284271247.461903
+1744061311.414722,5.781455039978027,0.057568652950039975,1744061311.4147239,5.781455039978027,-0.04252348721638441,1744061311.4147258,5.781455039978027,0.0033068568065808684,1744061311.414728,5.781455039978027,-56568542383.59709,1744061311.4147289,5.781455039978027,0.065,1744061311.4147303,5.781455039978027,3.1415926535878924,1744061311.414731,5.781455039978027,0.1075268590076117,1744061311.414732,5.781455039978027,1.5483867758008976e-22,1744061311.4147332,5.781455039978027,2.2939362872390587,1744061311.4147344,5.781455039978027,0.0,1744061311.4147353,5.781455039978027,-22627416996.134373,1744061311.4147363,5.781455039978027,0.0,1744061311.4147375,5.781455039978027,28284271247.461903
+1744061311.4349594,5.801480293273926,0.057568652950039975,1744061311.4349608,5.801480293273926,-0.04252348721638441,1744061311.434963,5.801480293273926,0.0033068568065808684,1744061311.4349651,5.801480293273926,-56568542383.59709,1744061311.4349663,5.801480293273926,0.065,1744061311.4349675,5.801480293273926,3.1415926535878924,1744061311.4349685,5.801480293273926,0.1075268590076117,1744061311.4349697,5.801480293273926,1.5483867758008976e-22,1744061311.4349704,5.801480293273926,2.2939362872390587,1744061311.4349716,5.801480293273926,0.0,1744061311.4349725,5.801480293273926,-22627416996.134373,1744061311.4349737,5.801480293273926,0.0,1744061311.4349744,5.801480293273926,28284271247.461903
+1744061311.4553607,5.821472644805908,0.057568652950039975,1744061311.4553638,5.821472644805908,-0.04252348721638441,1744061311.4553673,5.821472644805908,0.0033068568065808684,1744061311.4553707,5.821472644805908,-56568542383.59709,1744061311.4553726,5.821472644805908,0.065,1744061311.4553745,5.821472644805908,3.1415926535878924,1744061311.4553766,5.821472644805908,0.1075268590076117,1744061311.4553778,5.821472644805908,1.5483867758008976e-22,1744061311.45538,5.821472644805908,2.2939362872390587,1744061311.4553823,5.821472644805908,0.0,1744061311.455384,5.821472644805908,-22627416996.134373,1744061311.455386,5.821472644805908,0.0,1744061311.4553876,5.821472644805908,28284271247.461903
+1744061311.4747403,5.841450929641724,0.057568652950039975,1744061311.474742,5.841450929641724,-0.04252348721638441,1744061311.4747446,5.841450929641724,0.0033068568065808684,1744061311.4747465,5.841450929641724,-56568542383.59709,1744061311.4747477,5.841450929641724,0.065,1744061311.4747488,5.841450929641724,3.1415926535878924,1744061311.47475,5.841450929641724,0.1075268590076117,1744061311.4747508,5.841450929641724,1.5483867758008976e-22,1744061311.4747517,5.841450929641724,2.2939362872390587,1744061311.4747531,5.841450929641724,0.0,1744061311.474754,5.841450929641724,-22627416996.134373,1744061311.474755,5.841450929641724,0.0,1744061311.474756,5.841450929641724,28284271247.461903
+1744061311.4949687,5.861458778381348,0.057568652950039975,1744061311.4949706,5.861458778381348,-0.04252348721638441,1744061311.494973,5.861458778381348,0.0033068568065808684,1744061311.494975,5.861458778381348,-56568542383.59709,1744061311.494976,5.861458778381348,0.065,1744061311.4949963,5.861458778381348,3.1415926535878924,1744061311.4949975,5.861458778381348,0.1075268590076117,1744061311.4949982,5.861458778381348,1.5483867758008976e-22,1744061311.4949994,5.861458778381348,2.2939362872390587,1744061311.4950006,5.861458778381348,0.0,1744061311.4950016,5.861458778381348,-22627416996.134373,1744061311.4950025,5.861458778381348,0.0,1744061311.4950035,5.861458778381348,28284271247.461903
+1744061311.5146422,5.881473779678345,0.057568652950039975,1744061311.514644,5.881473779678345,-0.04252348721638441,1744061311.5146463,5.881473779678345,0.0033068568065808684,1744061311.5146484,5.881473779678345,-56568542383.59709,1744061311.5146494,5.881473779678345,0.065,1744061311.5146503,5.881473779678345,3.1415926535878924,1744061311.5146513,5.881473779678345,0.1075268590076117,1744061311.5146525,5.881473779678345,1.5483867758008976e-22,1744061311.5146534,5.881473779678345,2.2939362872390587,1744061311.5146546,5.881473779678345,0.0,1744061311.5146558,5.881473779678345,-22627416996.134373,1744061311.5146565,5.881473779678345,0.0,1744061311.5146575,5.881473779678345,28284271247.461903
+1744061311.535285,5.901460409164429,0.057568652950039975,1744061311.5352886,5.901460409164429,-0.04252348721638441,1744061311.5352914,5.901460409164429,0.0033068568065808684,1744061311.5352936,5.901460409164429,-56568542383.59709,1744061311.5352955,5.901460409164429,0.065,1744061311.5352974,5.901460409164429,3.1415926535878924,1744061311.5352988,5.901460409164429,0.1075268590076117,1744061311.5352995,5.901460409164429,1.5483867758008976e-22,1744061311.5353005,5.901460409164429,2.2939362872390587,1744061311.5353022,5.901460409164429,0.0,1744061311.535303,5.901460409164429,-22627416996.134373,1744061311.5353045,5.901460409164429,0.0,1744061311.5353055,5.901460409164429,28284271247.461903
+1744061311.5547862,5.9214863777160645,0.057568652950039975,1744061311.554788,5.9214863777160645,-0.04252348721638441,1744061311.5547905,5.9214863777160645,0.0033068568065808684,1744061311.5547924,5.9214863777160645,-56568542383.59709,1744061311.5547934,5.9214863777160645,0.065,1744061311.5547948,5.9214863777160645,3.1415926535878924,1744061311.5547957,5.9214863777160645,0.1075268590076117,1744061311.5547965,5.9214863777160645,1.5483867758008976e-22,1744061311.5547976,5.9214863777160645,2.2939362872390587,1744061311.5547996,5.9214863777160645,0.0,1744061311.5548003,5.9214863777160645,-22627416996.134373,1744061311.5548017,5.9214863777160645,0.0,1744061311.5548024,5.9214863777160645,28284271247.461903
+1744061311.5749292,5.941517114639282,0.057568652950039975,1744061311.5749311,5.941517114639282,-0.04252348721638441,1744061311.5749333,5.941517114639282,0.0033068568065808684,1744061311.5749352,5.941517114639282,-56568542383.59709,1744061311.5749364,5.941517114639282,0.065,1744061311.5749378,5.941517114639282,3.1415926535878924,1744061311.5749393,5.941517114639282,0.1075268590076117,1744061311.57494,5.941517114639282,1.5483867758008976e-22,1744061311.574941,5.941517114639282,2.2939362872390587,1744061311.5749424,5.941517114639282,0.0,1744061311.5749433,5.941517114639282,-22627416996.134373,1744061311.5749443,5.941517114639282,0.0,1744061311.5749452,5.941517114639282,28284271247.461903
+1744061311.5949519,5.961459398269653,0.057568652950039975,1744061311.5949538,5.961459398269653,-0.04252348721638441,1744061311.5949557,5.961459398269653,0.0033068568065808684,1744061311.5949578,5.961459398269653,-56568542383.59709,1744061311.594959,5.961459398269653,0.065,1744061311.5949602,5.961459398269653,3.1415926535878924,1744061311.5949614,5.961459398269653,0.1075268590076117,1744061311.5949624,5.961459398269653,1.5483867758008976e-22,1744061311.5949636,5.961459398269653,2.2939362872390587,1744061311.5949647,5.961459398269653,0.0,1744061311.5949657,5.961459398269653,-22627416996.134373,1744061311.5949671,5.961459398269653,0.0,1744061311.5949678,5.961459398269653,28284271247.461903
+1744061311.6147695,5.981483697891235,0.057568652950039975,1744061311.6147711,5.981483697891235,-0.04252348721638441,1744061311.6147733,5.981483697891235,0.0033068568065808684,1744061311.6147752,5.981483697891235,-56568542383.59709,1744061311.6147766,5.981483697891235,0.065,1744061311.6147776,5.981483697891235,3.1415926535878924,1744061311.614779,5.981483697891235,0.1075268590076117,1744061311.6147797,5.981483697891235,1.5483867758008976e-22,1744061311.6147807,5.981483697891235,2.2939362872390587,1744061311.614782,5.981483697891235,0.0,1744061311.6147833,5.981483697891235,-22627416996.134373,1744061311.6147842,5.981483697891235,0.0,1744061311.614785,5.981483697891235,28284271247.461903
+1744061311.6349676,6.001487493515015,0.057568652950039975,1744061311.634969,6.001487493515015,-0.04252348721638441,1744061311.6349711,6.001487493515015,0.0033068568065808684,1744061311.6349733,6.001487493515015,-56568542383.59709,1744061311.6349742,6.001487493515015,0.065,1744061311.6349757,6.001487493515015,3.1415926535878924,1744061311.6349769,6.001487493515015,0.1075268590076117,1744061311.6349778,6.001487493515015,1.5483867758008976e-22,1744061311.6349785,6.001487493515015,2.2939362872390587,1744061311.6349797,6.001487493515015,0.0,1744061311.634981,6.001487493515015,-22627416996.134373,1744061311.6349819,6.001487493515015,0.0,1744061311.6349826,6.001487493515015,28284271247.461903
+1744061311.6549373,6.0214715003967285,0.057568652950039975,1744061311.6549394,6.0214715003967285,-0.04252348721638441,1744061311.6549418,6.0214715003967285,0.0033068568065808684,1744061311.6549437,6.0214715003967285,-56568542383.59709,1744061311.6549454,6.0214715003967285,0.065,1744061311.6549466,6.0214715003967285,3.1415926535878924,1744061311.6549475,6.0214715003967285,0.1075268590076117,1744061311.6549487,6.0214715003967285,1.5483867758008976e-22,1744061311.6549497,6.0214715003967285,2.2939362872390587,1744061311.654951,6.0214715003967285,0.0,1744061311.6549523,6.0214715003967285,-22627416996.134373,1744061311.6549532,6.0214715003967285,0.0,1744061311.6549542,6.0214715003967285,28284271247.461903
+1744061311.6747353,6.04148268699646,0.057568652950039975,1744061311.6747375,6.04148268699646,-0.04252348721638441,1744061311.6747396,6.04148268699646,0.0033068568065808684,1744061311.6747417,6.04148268699646,-56568542383.59709,1744061311.674743,6.04148268699646,0.065,1744061311.6747444,6.04148268699646,3.1415926535878924,1744061311.6747453,6.04148268699646,0.1075268590076117,1744061311.6747463,6.04148268699646,1.5483867758008976e-22,1744061311.6747475,6.04148268699646,2.2939362872390587,1744061311.674749,6.04148268699646,0.0,1744061311.6747499,6.04148268699646,-22627416996.134373,1744061311.674751,6.04148268699646,0.0,1744061311.674752,6.04148268699646,28284271247.461903
+1744061311.6958325,6.061481952667236,0.057568652950039975,1744061311.6958363,6.061481952667236,-0.04252348721638441,1744061311.695841,6.061481952667236,0.0033068568065808684,1744061311.6958454,6.061481952667236,-56568542383.59709,1744061311.695848,6.061481952667236,0.065,1744061311.6958508,6.061481952667236,3.1415926535878924,1744061311.6958532,6.061481952667236,0.1075268590076117,1744061311.6958556,6.061481952667236,1.5483867758008976e-22,1744061311.6958578,6.061481952667236,2.2939362872390587,1744061311.6958606,6.061481952667236,0.0,1744061311.6958632,6.061481952667236,-22627416996.134373,1744061311.6958659,6.061481952667236,0.0,1744061311.6958685,6.061481952667236,28284271247.461903
+1744061311.714681,6.081480979919434,0.057568652950039975,1744061311.7146828,6.081480979919434,-0.04252348721638441,1744061311.7146854,6.081480979919434,0.0033068568065808684,1744061311.7146876,6.081480979919434,-56568542383.59709,1744061311.7146885,6.081480979919434,0.065,1744061311.7146902,6.081480979919434,3.1415926535878924,1744061311.7146914,6.081480979919434,0.1075268590076117,1744061311.7146924,6.081480979919434,1.5483867758008976e-22,1744061311.7146933,6.081480979919434,2.2939362872390587,1744061311.714695,6.081480979919434,0.0,1744061311.714696,6.081480979919434,-22627416996.134373,1744061311.714697,6.081480979919434,0.0,1744061311.714698,6.081480979919434,28284271247.461903
+1744061311.7349324,6.101482152938843,0.057568652950039975,1744061311.7349343,6.101482152938843,-0.04252348721638441,1744061311.7349365,6.101482152938843,0.0033068568065808684,1744061311.7349389,6.101482152938843,-56568542383.59709,1744061311.7349398,6.101482152938843,0.065,1744061311.7349412,6.101482152938843,3.1415926535878924,1744061311.7349424,6.101482152938843,0.1075268590076117,1744061311.7349434,6.101482152938843,1.5483867758008976e-22,1744061311.7349446,6.101482152938843,2.2939362872390587,1744061311.734946,6.101482152938843,0.0,1744061311.7349467,6.101482152938843,-22627416996.134373,1744061311.734948,6.101482152938843,0.0,1744061311.7349489,6.101482152938843,28284271247.461903
+1744061311.755061,6.121472597122192,0.057568652950039975,1744061311.7550645,6.121472597122192,-0.04252348721638441,1744061311.7550688,6.121472597122192,0.0033068568065808684,1744061311.755071,6.121472597122192,-56568542383.59709,1744061311.7550724,6.121472597122192,0.065,1744061311.7550738,6.121472597122192,3.1415926535878924,1744061311.755075,6.121472597122192,0.1075268590076117,1744061311.7550762,6.121472597122192,1.5483867758008976e-22,1744061311.7550774,6.121472597122192,2.2939362872390587,1744061311.755079,6.121472597122192,0.0,1744061311.75508,6.121472597122192,-22627416996.134373,1744061311.755081,6.121472597122192,0.0,1744061311.755082,6.121472597122192,28284271247.461903
+1744061311.7747257,6.141451358795166,0.057568652950039975,1744061311.7747276,6.141451358795166,-0.04252348721638441,1744061311.77473,6.141451358795166,0.0033068568065808684,1744061311.774732,6.141451358795166,-56568542383.59709,1744061311.774733,6.141451358795166,0.065,1744061311.7747343,6.141451358795166,3.1415926535878924,1744061311.7747355,6.141451358795166,0.1075268590076117,1744061311.7747364,6.141451358795166,1.5483867758008976e-22,1744061311.7747374,6.141451358795166,2.2939362872390587,1744061311.7747388,6.141451358795166,0.0,1744061311.7747397,6.141451358795166,-22627416996.134373,1744061311.7747412,6.141451358795166,0.0,1744061311.7747421,6.141451358795166,28284271247.461903
+1744061311.7947118,6.161479234695435,0.057568652950039975,1744061311.794714,6.161479234695435,-0.04252348721638441,1744061311.794716,6.161479234695435,0.0033068568065808684,1744061311.794718,6.161479234695435,-56568542383.59709,1744061311.794719,6.161479234695435,0.065,1744061311.7947202,6.161479234695435,3.1415926535878924,1744061311.7947216,6.161479234695435,0.1075268590076117,1744061311.7947223,6.161479234695435,1.5483867758008976e-22,1744061311.7947233,6.161479234695435,2.2939362872390587,1744061311.794725,6.161479234695435,0.0,1744061311.794726,6.161479234695435,-22627416996.134373,1744061311.7947268,6.161479234695435,0.0,1744061311.7947276,6.161479234695435,28284271247.461903
+1744061311.8146667,6.1814446449279785,0.057568652950039975,1744061311.8146687,6.1814446449279785,-0.04252348721638441,1744061311.8146708,6.1814446449279785,0.0033068568065808684,1744061311.814673,6.1814446449279785,-56568542383.59709,1744061311.814674,6.1814446449279785,0.065,1744061311.8146756,6.1814446449279785,3.1415926535878924,1744061311.8146768,6.1814446449279785,0.1075268590076117,1744061311.8146775,6.1814446449279785,1.5483867758008976e-22,1744061311.8146784,6.1814446449279785,2.2939362872390587,1744061311.81468,6.1814446449279785,0.0,1744061311.814681,6.1814446449279785,-22627416996.134373,1744061311.814682,6.1814446449279785,0.0,1744061311.8146832,6.1814446449279785,28284271247.461903
+1744061311.834825,6.201446533203125,0.04187635218957385,1744061311.8348267,6.201446533203125,-0.06478018706588368,1744061311.8348286,6.201446533203125,0.0033006036927579014,1744061311.8348305,6.201446533203125,-56568542383.59709,1744061311.8348317,6.201446533203125,0.065,1744061311.834833,6.201446533203125,3.141592653587499,1744061311.8348339,6.201446533203125,0.1297844896580966,1744061311.834835,6.201446533203125,1.8688966584297895e-22,1744061311.834836,6.201446533203125,2.253451723784611,1744061311.8348372,6.201446533203125,0.0,1744061311.834838,6.201446533203125,-22627416996.178917,1744061311.834839,6.201446533203125,0.0,1744061311.83484,6.201446533203125,28284271247.461903
+1744061311.854815,6.221459627151489,0.04187635218957385,1744061311.854818,6.221459627151489,-0.06478018706588368,1744061311.85482,6.221459627151489,0.0033006036927579014,1744061311.8548222,6.221459627151489,-56568542383.59709,1744061311.8548234,6.221459627151489,0.065,1744061311.8548248,6.221459627151489,3.141592653587499,1744061311.854826,6.221459627151489,0.1297844896580966,1744061311.8548267,6.221459627151489,1.8688966584297895e-22,1744061311.854828,6.221459627151489,2.253451723784611,1744061311.8548298,6.221459627151489,0.0,1744061311.8548305,6.221459627151489,-22627416996.166763,1744061311.854832,6.221459627151489,0.0,1744061311.8548326,6.221459627151489,28284271247.461903
+1744061311.87469,6.241447925567627,0.04187635218957385,1744061311.8746917,6.241447925567627,-0.06478018706588368,1744061311.8746939,6.241447925567627,0.0033006036927579014,1744061311.8746963,6.241447925567627,-56568542383.59709,1744061311.8746972,6.241447925567627,0.065,1744061311.8746986,6.241447925567627,3.141592653587499,1744061311.8746998,6.241447925567627,0.1297844896580966,1744061311.8747005,6.241447925567627,1.8688966584297895e-22,1744061311.8747015,6.241447925567627,2.253451723784611,1744061311.874703,6.241447925567627,0.0,1744061311.874704,6.241447925567627,-22627416996.166763,1744061311.8747048,6.241447925567627,0.0,1744061311.8747056,6.241447925567627,28284271247.461903
+1744061311.8948843,6.261461019515991,0.04187635218957385,1744061311.8948863,6.261461019515991,-0.06478018706588368,1744061311.8948884,6.261461019515991,0.0033006036927579014,1744061311.8948905,6.261461019515991,-56568542383.59709,1744061311.8948915,6.261461019515991,0.065,1744061311.8948927,6.261461019515991,3.141592653587499,1744061311.894894,6.261461019515991,0.1297844896580966,1744061311.8948948,6.261461019515991,1.8688966584297895e-22,1744061311.8948958,6.261461019515991,2.253451723784611,1744061311.8948975,6.261461019515991,0.0,1744061311.8948984,6.261461019515991,-22627416996.166763,1744061311.8948994,6.261461019515991,0.0,1744061311.8949003,6.261461019515991,28284271247.461903
+1744061311.9146924,6.281483888626099,0.04187635218957385,1744061311.9146955,6.281483888626099,-0.06478018706588368,1744061311.9146981,6.281483888626099,0.0033006036927579014,1744061311.9147012,6.281483888626099,-56568542383.59709,1744061311.9147031,6.281483888626099,0.065,1744061311.9147048,6.281483888626099,3.141592653587499,1744061311.9147065,6.281483888626099,0.1297844896580966,1744061311.914708,6.281483888626099,1.8688966584297895e-22,1744061311.9147177,6.281483888626099,2.253451723784611,1744061311.9147196,6.281483888626099,0.0,1744061311.9147205,6.281483888626099,-22627416996.166763,1744061311.914722,6.281483888626099,0.0,1744061311.9147236,6.281483888626099,28284271247.461903
+1744061311.9350538,6.301474571228027,0.04187635218957385,1744061311.9350557,6.301474571228027,-0.06478018706588368,1744061311.9350576,6.301474571228027,0.0033006036927579014,1744061311.9350598,6.301474571228027,-56568542383.59709,1744061311.9350607,6.301474571228027,0.065,1744061311.9350617,6.301474571228027,3.141592653587499,1744061311.935063,6.301474571228027,0.1297844896580966,1744061311.9350638,6.301474571228027,1.8688966584297895e-22,1744061311.9350648,6.301474571228027,2.253451723784611,1744061311.9350662,6.301474571228027,0.0,1744061311.935067,6.301474571228027,-22627416996.166763,1744061311.935068,6.301474571228027,0.0,1744061311.9350688,6.301474571228027,28284271247.461903
+1744061311.9551806,6.321489095687866,0.04187635218957385,1744061311.955184,6.321489095687866,-0.06478018706588368,1744061311.9551868,6.321489095687866,0.0033006036927579014,1744061311.955189,6.321489095687866,-56568542383.59709,1744061311.9551904,6.321489095687866,0.065,1744061311.955192,6.321489095687866,3.141592653587499,1744061311.9551938,6.321489095687866,0.1297844896580966,1744061311.955195,6.321489095687866,1.8688966584297895e-22,1744061311.9551961,6.321489095687866,2.253451723784611,1744061311.9551988,6.321489095687866,0.0,1744061311.9551995,6.321489095687866,-22627416996.166763,1744061311.9552016,6.321489095687866,0.0,1744061311.9552028,6.321489095687866,28284271247.461903
+1744061311.9747834,6.341450452804565,0.04187635218957385,1744061311.9747858,6.341450452804565,-0.06478018706588368,1744061311.9747884,6.341450452804565,0.0033006036927579014,1744061311.9747903,6.341450452804565,-56568542383.59709,1744061311.9747915,6.341450452804565,0.065,1744061311.9747927,6.341450452804565,3.141592653587499,1744061311.974794,6.341450452804565,0.1297844896580966,1744061311.9747949,6.341450452804565,1.8688966584297895e-22,1744061311.9747958,6.341450452804565,2.253451723784611,1744061311.974797,6.341450452804565,0.0,1744061311.974798,6.341450452804565,-22627416996.166763,1744061311.9747992,6.341450452804565,0.0,1744061311.9748,6.341450452804565,28284271247.461903
+1744061311.9948497,6.361483812332153,0.04187635218957385,1744061311.994852,6.361483812332153,-0.06478018706588368,1744061311.9948545,6.361483812332153,0.0033006036927579014,1744061311.9948564,6.361483812332153,-56568542383.59709,1744061311.9948578,6.361483812332153,0.065,1744061311.994859,6.361483812332153,3.141592653587499,1744061311.9948602,6.361483812332153,0.1297844896580966,1744061311.9948614,6.361483812332153,1.8688966584297895e-22,1744061311.994862,6.361483812332153,2.253451723784611,1744061311.994864,6.361483812332153,0.0,1744061311.9948647,6.361483812332153,-22627416996.166763,1744061311.994866,6.361483812332153,0.0,1744061311.9948666,6.361483812332153,28284271247.461903
+1744061312.014723,6.381448030471802,0.04187635218957385,1744061312.014725,6.381448030471802,-0.06478018706588368,1744061312.014727,6.381448030471802,0.0033006036927579014,1744061312.0147293,6.381448030471802,-56568542383.59709,1744061312.0147305,6.381448030471802,0.065,1744061312.014732,6.381448030471802,3.141592653587499,1744061312.0147328,6.381448030471802,0.1297844896580966,1744061312.0147336,6.381448030471802,1.8688966584297895e-22,1744061312.0147345,6.381448030471802,2.253451723784611,1744061312.0147362,6.381448030471802,0.0,1744061312.014737,6.381448030471802,-22627416996.166763,1744061312.014738,6.381448030471802,0.0,1744061312.014739,6.381448030471802,28284271247.461903
+1744061312.0353346,6.401448488235474,0.04187635218957385,1744061312.0353367,6.401448488235474,-0.06478018706588368,1744061312.035339,6.401448488235474,0.0033006036927579014,1744061312.0353415,6.401448488235474,-56568542383.59709,1744061312.0353436,6.401448488235474,0.065,1744061312.035346,6.401448488235474,3.141592653587499,1744061312.0353477,6.401448488235474,0.1297844896580966,1744061312.0353496,6.401448488235474,1.8688966584297895e-22,1744061312.0353506,6.401448488235474,2.253451723784611,1744061312.0353518,6.401448488235474,0.0,1744061312.035353,6.401448488235474,-22627416996.166763,1744061312.0353541,6.401448488235474,0.0,1744061312.035355,6.401448488235474,28284271247.461903
+1744061312.0551572,6.421490430831909,0.04187635218957385,1744061312.0551605,6.421490430831909,-0.06478018706588368,1744061312.0551636,6.421490430831909,0.0033006036927579014,1744061312.055166,6.421490430831909,-56568542383.59709,1744061312.0551672,6.421490430831909,0.065,1744061312.055169,6.421490430831909,3.141592653587499,1744061312.055171,6.421490430831909,0.1297844896580966,1744061312.0551724,6.421490430831909,1.8688966584297895e-22,1744061312.0551739,6.421490430831909,2.253451723784611,1744061312.0551763,6.421490430831909,0.0,1744061312.0551775,6.421490430831909,-22627416996.166763,1744061312.055179,6.421490430831909,0.0,1744061312.0551803,6.421490430831909,28284271247.461903
+1744061312.0746152,6.441447496414185,0.04187635218957385,1744061312.0746171,6.441447496414185,-0.06478018706588368,1744061312.0746193,6.441447496414185,0.0033006036927579014,1744061312.0746214,6.441447496414185,-56568542383.59709,1744061312.0746224,6.441447496414185,0.065,1744061312.0746238,6.441447496414185,3.141592653587499,1744061312.0746248,6.441447496414185,0.1297844896580966,1744061312.0746257,6.441447496414185,1.8688966584297895e-22,1744061312.074627,6.441447496414185,2.253451723784611,1744061312.074628,6.441447496414185,0.0,1744061312.074629,6.441447496414185,-22627416996.166763,1744061312.0746303,6.441447496414185,0.0,1744061312.074631,6.441447496414185,28284271247.461903
+1744061312.0948498,6.461524248123169,0.04187635218957385,1744061312.0948515,6.461524248123169,-0.06478018706588368,1744061312.0948539,6.461524248123169,0.0033006036927579014,1744061312.094856,6.461524248123169,-56568542383.59709,1744061312.094857,6.461524248123169,0.065,1744061312.0948582,6.461524248123169,3.141592653587499,1744061312.0948594,6.461524248123169,0.1297844896580966,1744061312.0948603,6.461524248123169,1.8688966584297895e-22,1744061312.0948615,6.461524248123169,2.253451723784611,1744061312.0948632,6.461524248123169,0.0,1744061312.0948641,6.461524248123169,-22627416996.166763,1744061312.094865,6.461524248123169,0.0,1744061312.0948663,6.461524248123169,28284271247.461903
+1744061312.1146555,6.481446027755737,0.04187635218957385,1744061312.1146576,6.481446027755737,-0.06478018706588368,1744061312.1146598,6.481446027755737,0.0033006036927579014,1744061312.114662,6.481446027755737,-56568542383.59709,1744061312.114663,6.481446027755737,0.065,1744061312.114664,6.481446027755737,3.141592653587499,1744061312.1146653,6.481446027755737,0.1297844896580966,1744061312.1146662,6.481446027755737,1.8688966584297895e-22,1744061312.1146672,6.481446027755737,2.253451723784611,1744061312.1146686,6.481446027755737,0.0,1744061312.1146696,6.481446027755737,-22627416996.166763,1744061312.1146705,6.481446027755737,0.0,1744061312.1146717,6.481446027755737,28284271247.461903
+1744061312.1350799,6.501451730728149,0.04187635218957385,1744061312.1350827,6.501451730728149,-0.06478018706588368,1744061312.1350853,6.501451730728149,0.0033006036927579014,1744061312.1350884,6.501451730728149,-56568542383.59709,1744061312.1350906,6.501451730728149,0.065,1744061312.1350925,6.501451730728149,3.141592653587499,1744061312.1350935,6.501451730728149,0.1297844896580966,1744061312.1350946,6.501451730728149,1.8688966584297895e-22,1744061312.1350956,6.501451730728149,2.253451723784611,1744061312.135097,6.501451730728149,0.0,1744061312.1350977,6.501451730728149,-22627416996.166763,1744061312.1350992,6.501451730728149,0.0,1744061312.1351001,6.501451730728149,28284271247.461903
+1744061312.1548877,6.521456956863403,0.04187635218957385,1744061312.1548898,6.521456956863403,-0.06478018706588368,1744061312.1548917,6.521456956863403,0.0033006036927579014,1744061312.1548936,6.521456956863403,-56568542383.59709,1744061312.1548948,6.521456956863403,0.065,1744061312.154896,6.521456956863403,3.141592653587499,1744061312.1548972,6.521456956863403,0.1297844896580966,1744061312.154898,6.521456956863403,1.8688966584297895e-22,1744061312.1548991,6.521456956863403,2.253451723784611,1744061312.1549008,6.521456956863403,0.0,1744061312.1549017,6.521456956863403,-22627416996.166763,1744061312.154903,6.521456956863403,0.0,1744061312.1549041,6.521456956863403,28284271247.461903
+1744061312.1747334,6.541465520858765,0.04187635218957385,1744061312.1747353,6.541465520858765,-0.06478018706588368,1744061312.1747377,6.541465520858765,0.0033006036927579014,1744061312.1747396,6.541465520858765,-56568542383.59709,1744061312.174741,6.541465520858765,0.065,1744061312.1747422,6.541465520858765,3.141592653587499,1744061312.1747434,6.541465520858765,0.1297844896580966,1744061312.1747444,6.541465520858765,1.8688966584297895e-22,1744061312.1747453,6.541465520858765,2.253451723784611,1744061312.1747465,6.541465520858765,0.0,1744061312.1747475,6.541465520858765,-22627416996.166763,1744061312.1747487,6.541465520858765,0.0,1744061312.1747496,6.541465520858765,28284271247.461903
+1744061312.1961472,6.561570405960083,0.04187635218957385,1744061312.196149,6.561570405960083,-0.06478018706588368,1744061312.1961513,6.561570405960083,0.0033006036927579014,1744061312.1961534,6.561570405960083,-56568542383.59709,1744061312.1961544,6.561570405960083,0.065,1744061312.1961555,6.561570405960083,3.141592653587499,1744061312.1961567,6.561570405960083,0.1297844896580966,1744061312.1961577,6.561570405960083,1.8688966584297895e-22,1744061312.1961586,6.561570405960083,2.253451723784611,1744061312.19616,6.561570405960083,0.0,1744061312.196161,6.561570405960083,-22627416996.166763,1744061312.1961622,6.561570405960083,0.0,1744061312.1961637,6.561570405960083,28284271247.461903
+1744061312.2146192,6.581442832946777,0.04187635218957385,1744061312.214621,6.581442832946777,-0.06478018706588368,1744061312.2146232,6.581442832946777,0.0033006036927579014,1744061312.2146254,6.581442832946777,-56568542383.59709,1744061312.2146266,6.581442832946777,0.065,1744061312.2146275,6.581442832946777,3.141592653587499,1744061312.214629,6.581442832946777,0.1297844896580966,1744061312.2146297,6.581442832946777,1.8688966584297895e-22,1744061312.2146304,6.581442832946777,2.253451723784611,1744061312.214632,6.581442832946777,0.0,1744061312.2146327,6.581442832946777,-22627416996.166763,1744061312.2146337,6.581442832946777,0.0,1744061312.2146347,6.581442832946777,28284271247.461903
+1744061312.234948,6.601480007171631,0.04187635218957385,1744061312.2349496,6.601480007171631,-0.06478018706588368,1744061312.2349517,6.601480007171631,0.0033006036927579014,1744061312.2349536,6.601480007171631,-56568542383.59709,1744061312.2349548,6.601480007171631,0.065,1744061312.2349558,6.601480007171631,3.141592653587499,1744061312.2349567,6.601480007171631,0.1297844896580966,1744061312.234958,6.601480007171631,1.8688966584297895e-22,1744061312.234959,6.601480007171631,2.253451723784611,1744061312.23496,6.601480007171631,0.0,1744061312.234961,6.601480007171631,-22627416996.166763,1744061312.2349622,6.601480007171631,0.0,1744061312.234963,6.601480007171631,28284271247.461903
+1744061312.2548108,6.621486186981201,0.04187635218957385,1744061312.254813,6.621486186981201,-0.06478018706588368,1744061312.2548149,6.621486186981201,0.0033006036927579014,1744061312.254817,6.621486186981201,-56568542383.59709,1744061312.2548182,6.621486186981201,0.065,1744061312.2548196,6.621486186981201,3.141592653587499,1744061312.2548206,6.621486186981201,0.1297844896580966,1744061312.2548213,6.621486186981201,1.8688966584297895e-22,1744061312.2548225,6.621486186981201,2.253451723784611,1744061312.2548237,6.621486186981201,0.0,1744061312.2548246,6.621486186981201,-22627416996.166763,1744061312.2548258,6.621486186981201,0.0,1744061312.2548268,6.621486186981201,28284271247.461903
+1744061312.274648,6.641470670700073,0.04187635218957385,1744061312.2746499,6.641470670700073,-0.06478018706588368,1744061312.2746522,6.641470670700073,0.0033006036927579014,1744061312.2746542,6.641470670700073,-56568542383.59709,1744061312.2746556,6.641470670700073,0.065,1744061312.2746568,6.641470670700073,3.141592653587499,1744061312.2746577,6.641470670700073,0.1297844896580966,1744061312.2746584,6.641470670700073,1.8688966584297895e-22,1744061312.2746596,6.641470670700073,2.253451723784611,1744061312.2746608,6.641470670700073,0.0,1744061312.2746618,6.641470670700073,-22627416996.166763,1744061312.274663,6.641470670700073,0.0,1744061312.274664,6.641470670700073,28284271247.461903
+1744061312.2946818,6.6614439487457275,0.04187635218957385,1744061312.2946837,6.6614439487457275,-0.06478018706588368,1744061312.2946856,6.6614439487457275,0.0033006036927579014,1744061312.2946877,6.6614439487457275,-56568542383.59709,1744061312.2946887,6.6614439487457275,0.065,1744061312.2946901,6.6614439487457275,3.141592653587499,1744061312.294691,6.6614439487457275,0.1297844896580966,1744061312.294692,6.6614439487457275,1.8688966584297895e-22,1744061312.2946932,6.6614439487457275,2.253451723784611,1744061312.2946947,6.6614439487457275,0.0,1744061312.2946954,6.6614439487457275,-22627416996.166763,1744061312.2946968,6.6614439487457275,0.0,1744061312.2946975,6.6614439487457275,28284271247.461903
+1744061312.314734,6.6814799308776855,0.04187635218957385,1744061312.314736,6.6814799308776855,-0.06478018706588368,1744061312.3147383,6.6814799308776855,0.0033006036927579014,1744061312.3147402,6.6814799308776855,-56568542383.59709,1744061312.3147411,6.6814799308776855,0.065,1744061312.3147428,6.6814799308776855,3.141592653587499,1744061312.314744,6.6814799308776855,0.1297844896580966,1744061312.314745,6.6814799308776855,1.8688966584297895e-22,1744061312.314746,6.6814799308776855,2.253451723784611,1744061312.3147473,6.6814799308776855,0.0,1744061312.3147485,6.6814799308776855,-22627416996.166763,1744061312.3147495,6.6814799308776855,0.0,1744061312.3147502,6.6814799308776855,28284271247.461903
+1744061312.335445,6.701514005661011,-0.041517475583801575,1744061312.3354483,6.701514005661011,-0.35800444603794385,1744061312.335452,6.701514005661011,0.0013530044460379439,1744061312.3354554,6.701514005661011,-56568542383.59514,1744061312.3354578,6.701514005661011,0.065,1744061312.3354592,6.701514005661011,3.1415926535823155,1744061312.3354607,6.701514005661011,0.4230023959247359,1744061312.3354614,6.701514005661011,6.091234525300619e-22,1744061312.3354623,6.701514005661011,1.7822717509233952,1744061312.3354642,6.701514005661011,0.0,1744061312.3354652,6.701514005661011,-22627416996.68466,1744061312.3354669,6.701514005661011,0.0,1744061312.3354678,6.701514005661011,28284271247.461903
+1744061312.354695,6.721478700637817,-0.041517475583801575,1744061312.3546972,6.721478700637817,-0.35800444603794385,1744061312.3546994,6.721478700637817,0.0013530044460379439,1744061312.3547013,6.721478700637817,-56568542383.59514,1744061312.3547022,6.721478700637817,0.065,1744061312.3547037,6.721478700637817,3.1415926535823155,1744061312.3547046,6.721478700637817,0.4230023959247359,1744061312.3547056,6.721478700637817,6.091234525300619e-22,1744061312.354707,6.721478700637817,1.7822717509233952,1744061312.3547082,6.721478700637817,0.0,1744061312.3547091,6.721478700637817,-22627416996.543705,1744061312.3547106,6.721478700637817,0.0,1744061312.3547115,6.721478700637817,28284271247.461903
+1744061312.3746662,6.7414751052856445,-0.041517475583801575,1744061312.3746684,6.7414751052856445,-0.35800444603794385,1744061312.3746703,6.7414751052856445,0.0013530044460379439,1744061312.3746724,6.7414751052856445,-56568542383.59514,1744061312.3746734,6.7414751052856445,0.065,1744061312.3746748,6.7414751052856445,3.1415926535823155,1744061312.3746758,6.7414751052856445,0.4230023959247359,1744061312.3746767,6.7414751052856445,6.091234525300619e-22,1744061312.3746774,6.7414751052856445,1.7822717509233952,1744061312.3746793,6.7414751052856445,0.0,1744061312.37468,6.7414751052856445,-22627416996.543705,1744061312.374681,6.7414751052856445,0.0,1744061312.3746822,6.7414751052856445,28284271247.461903
+1744061312.3946576,6.761444330215454,-0.041517475583801575,1744061312.394659,6.761444330215454,-0.35800444603794385,1744061312.3946612,6.761444330215454,0.0013530044460379439,1744061312.394663,6.761444330215454,-56568542383.59514,1744061312.3946643,6.761444330215454,0.065,1744061312.3946655,6.761444330215454,3.1415926535823155,1744061312.3946664,6.761444330215454,0.4230023959247359,1744061312.3946676,6.761444330215454,6.091234525300619e-22,1744061312.3946686,6.761444330215454,1.7822717509233952,1744061312.3946698,6.761444330215454,0.0,1744061312.3946705,6.761444330215454,-22627416996.543705,1744061312.394672,6.761444330215454,0.0,1744061312.3946729,6.761444330215454,28284271247.461903
+1744061312.4147277,6.781474828720093,-0.041517475583801575,1744061312.4147294,6.781474828720093,-0.35800444603794385,1744061312.4147317,6.781474828720093,0.0013530044460379439,1744061312.414734,6.781474828720093,-56568542383.59514,1744061312.4147348,6.781474828720093,0.065,1744061312.414736,6.781474828720093,3.1415926535823155,1744061312.4147372,6.781474828720093,0.4230023959247359,1744061312.4147382,6.781474828720093,6.091234525300619e-22,1744061312.414739,6.781474828720093,1.7822717509233952,1744061312.4147406,6.781474828720093,0.0,1744061312.4147413,6.781474828720093,-22627416996.543705,1744061312.4147422,6.781474828720093,0.0,1744061312.4147432,6.781474828720093,28284271247.461903
+1744061312.4349449,6.801490306854248,-0.04151747484243354,1744061312.4349465,6.801490306854248,-0.3580044463077798,1744061312.4349487,6.801490306854248,0.0013530044463077797,1744061312.4349506,6.801490306854248,-56568542383.59514,1744061312.4349518,6.801490306854248,0.065,1744061312.4349532,6.801490306854248,3.1415926535823155,1744061312.4349542,6.801490306854248,0.4230023959247359,1744061312.4349554,6.801490306854248,6.091234525300619e-22,1744061312.4349563,6.801490306854248,1.7822717509233952,1744061312.4349575,6.801490306854248,0.0,1744061312.4349582,6.801490306854248,-22627416996.543705,1744061312.4349594,6.801490306854248,0.0,1744061312.4349604,6.801490306854248,28284271247.461903
+1744061312.4548118,6.821455955505371,-0.04151747484243354,1744061312.454814,6.821455955505371,-0.3580044463077798,1744061312.454816,6.821455955505371,0.0013530044463077797,1744061312.4548182,6.821455955505371,-56568542383.59514,1744061312.4548194,6.821455955505371,0.065,1744061312.4548206,6.821455955505371,3.1415926535823155,1744061312.4548218,6.821455955505371,0.4230023959247359,1744061312.454823,6.821455955505371,6.091234525300619e-22,1744061312.454824,6.821455955505371,1.7822717509233952,1744061312.4548254,6.821455955505371,0.0,1744061312.4548266,6.821455955505371,-22627416996.543705,1744061312.4548278,6.821455955505371,0.0,1744061312.4548287,6.821455955505371,28284271247.461903
+1744061312.4746926,6.841444969177246,-0.04151747484243354,1744061312.4746947,6.841444969177246,-0.3580044463077798,1744061312.4746966,6.841444969177246,0.0013530044463077797,1744061312.4746988,6.841444969177246,-56568542383.59514,1744061312.4747,6.841444969177246,0.065,1744061312.4747014,6.841444969177246,3.1415926535823155,1744061312.4747024,6.841444969177246,0.4230023959247359,1744061312.474703,6.841444969177246,6.091234525300619e-22,1744061312.474704,6.841444969177246,1.7822717509233952,1744061312.4747055,6.841444969177246,0.0,1744061312.4747064,6.841444969177246,-22627416996.543705,1744061312.4747074,6.841444969177246,0.0,1744061312.4747086,6.841444969177246,28284271247.461903
+1744061312.4951773,6.861493110656738,-0.04151747484243354,1744061312.495179,6.861493110656738,-0.3580044463077798,1744061312.4951813,6.861493110656738,0.0013530044463077797,1744061312.4951835,6.861493110656738,-56568542383.59514,1744061312.4951844,6.861493110656738,0.065,1744061312.4951859,6.861493110656738,3.1415926535823155,1744061312.495187,6.861493110656738,0.4230023959247359,1744061312.495188,6.861493110656738,6.091234525300619e-22,1744061312.4951892,6.861493110656738,1.7822717509233952,1744061312.49521,6.861493110656738,0.0,1744061312.4952111,6.861493110656738,-22627416996.543705,1744061312.495212,6.861493110656738,0.0,1744061312.495213,6.861493110656738,28284271247.461903
+1744061312.5148265,6.881473541259766,-0.04151747484243354,1744061312.5148282,6.881473541259766,-0.3580044463077798,1744061312.5148306,6.881473541259766,0.0013530044463077797,1744061312.5148327,6.881473541259766,-56568542383.59514,1744061312.5148337,6.881473541259766,0.065,1744061312.514835,6.881473541259766,3.1415926535823155,1744061312.5148363,6.881473541259766,0.4230023959247359,1744061312.5148373,6.881473541259766,6.091234525300619e-22,1744061312.5148385,6.881473541259766,1.7822717509233952,1744061312.5148408,6.881473541259766,0.0,1744061312.5148423,6.881473541259766,-22627416996.543705,1744061312.514844,6.881473541259766,0.0,1744061312.5148456,6.881473541259766,28284271247.461903
+1744061312.5349052,6.901476621627808,-0.04151747484243354,1744061312.5349069,6.901476621627808,-0.3580044463077798,1744061312.5349088,6.901476621627808,0.0013530044463077797,1744061312.5349107,6.901476621627808,-56568542383.59514,1744061312.534912,6.901476621627808,0.065,1744061312.534913,6.901476621627808,3.1415926535823155,1744061312.534914,6.901476621627808,0.4230023959247359,1744061312.534915,6.901476621627808,6.091234525300619e-22,1744061312.5349162,6.901476621627808,1.7822717509233952,1744061312.534917,6.901476621627808,0.0,1744061312.534918,6.901476621627808,-22627416996.543705,1744061312.5349193,6.901476621627808,0.0,1744061312.5349202,6.901476621627808,28284271247.461903
+1744061312.55506,6.921457767486572,-0.04151747484243354,1744061312.555062,6.921457767486572,-0.3580044463077798,1744061312.5550642,6.921457767486572,0.0013530044463077797,1744061312.5550663,6.921457767486572,-56568542383.59514,1744061312.5550675,6.921457767486572,0.065,1744061312.5550687,6.921457767486572,3.1415926535823155,1744061312.5550697,6.921457767486572,0.4230023959247359,1744061312.5550706,6.921457767486572,6.091234525300619e-22,1744061312.5550716,6.921457767486572,1.7822717509233952,1744061312.5550733,6.921457767486572,0.0,1744061312.555074,6.921457767486572,-22627416996.543705,1744061312.5550754,6.921457767486572,0.0,1744061312.5550761,6.921457767486572,28284271247.461903
+1744061312.575166,6.94144606590271,-0.04151747484243354,1744061312.575168,6.94144606590271,-0.3580044463077798,1744061312.5751703,6.94144606590271,0.0013530044463077797,1744061312.5751724,6.94144606590271,-56568542383.59514,1744061312.5751736,6.94144606590271,0.065,1744061312.5751748,6.94144606590271,3.1415926535823155,1744061312.575176,6.94144606590271,0.4230023959247359,1744061312.575177,6.94144606590271,6.091234525300619e-22,1744061312.575178,6.94144606590271,1.7822717509233952,1744061312.5751796,6.94144606590271,0.0,1744061312.5751805,6.94144606590271,-22627416996.543705,1744061312.5751815,6.94144606590271,0.0,1744061312.5751827,6.94144606590271,28284271247.461903
+1744061312.5950112,6.961455583572388,-0.04151747484243354,1744061312.5950134,6.961455583572388,-0.3580044463077798,1744061312.5950158,6.961455583572388,0.0013530044463077797,1744061312.5950177,6.961455583572388,-56568542383.59514,1744061312.595019,6.961455583572388,0.065,1744061312.5950208,6.961455583572388,3.1415926535823155,1744061312.595022,6.961455583572388,0.4230023959247359,1744061312.595023,6.961455583572388,6.091234525300619e-22,1744061312.595024,6.961455583572388,1.7822717509233952,1744061312.595026,6.961455583572388,0.0,1744061312.595027,6.961455583572388,-22627416996.543705,1744061312.5950284,6.961455583572388,0.0,1744061312.5950294,6.961455583572388,28284271247.461903
+1744061312.6147497,6.981491804122925,-0.04151747484243354,1744061312.6147516,6.981491804122925,-0.3580044463077798,1744061312.6147535,6.981491804122925,0.0013530044463077797,1744061312.6147556,6.981491804122925,-56568542383.59514,1744061312.6147568,6.981491804122925,0.065,1744061312.6147583,6.981491804122925,3.1415926535823155,1744061312.6147592,6.981491804122925,0.4230023959247359,1744061312.61476,6.981491804122925,6.091234525300619e-22,1744061312.614761,6.981491804122925,1.7822717509233952,1744061312.6147625,6.981491804122925,0.0,1744061312.6147635,6.981491804122925,-22627416996.543705,1744061312.6147645,6.981491804122925,0.0,1744061312.6147656,6.981491804122925,28284271247.461903
+1744061312.634869,7.00144362449646,-0.04151747484243354,1744061312.6348708,7.00144362449646,-0.3580044463077798,1744061312.6348734,7.00144362449646,0.0013530044463077797,1744061312.6348753,7.00144362449646,-56568542383.59514,1744061312.6348767,7.00144362449646,0.065,1744061312.6348777,7.00144362449646,3.1415926535823155,1744061312.6348786,7.00144362449646,0.4230023959247359,1744061312.6348798,7.00144362449646,6.091234525300619e-22,1744061312.6348805,7.00144362449646,1.7822717509233952,1744061312.6348817,7.00144362449646,0.0,1744061312.6348825,7.00144362449646,-22627416996.543705,1744061312.6348836,7.00144362449646,0.0,1744061312.6348846,7.00144362449646,28284271247.461903
+1744061312.6548417,7.021461486816406,-0.04151747484243354,1744061312.654845,7.021461486816406,-0.3580044463077798,1744061312.6548479,7.021461486816406,0.0013530044463077797,1744061312.6548498,7.021461486816406,-56568542383.59514,1744061312.654851,7.021461486816406,0.065,1744061312.6548526,7.021461486816406,3.1415926535823155,1744061312.6548538,7.021461486816406,0.4230023959247359,1744061312.6548555,7.021461486816406,6.091234525300619e-22,1744061312.6548567,7.021461486816406,1.7822717509233952,1744061312.6548584,7.021461486816406,0.0,1744061312.6548595,7.021461486816406,-22627416996.543705,1744061312.6548605,7.021461486816406,0.0,1744061312.6548615,7.021461486816406,28284271247.461903
+1744061312.6747289,7.041452407836914,-0.04151747484243354,1744061312.6747308,7.041452407836914,-0.3580044463077798,1744061312.6747332,7.041452407836914,0.0013530044463077797,1744061312.674735,7.041452407836914,-56568542383.59514,1744061312.674736,7.041452407836914,0.065,1744061312.6747375,7.041452407836914,3.1415926535823155,1744061312.6747384,7.041452407836914,0.4230023959247359,1744061312.6747394,7.041452407836914,6.091234525300619e-22,1744061312.6747408,7.041452407836914,1.7822717509233952,1744061312.6747427,7.041452407836914,0.0,1744061312.6747437,7.041452407836914,-22627416996.543705,1744061312.6747448,7.041452407836914,0.0,1744061312.6747456,7.041452407836914,28284271247.461903
+1744061312.695113,7.061464071273804,-0.04151747484243354,1744061312.6951153,7.061464071273804,-0.3580044463077798,1744061312.6951182,7.061464071273804,0.0013530044463077797,1744061312.69512,7.061464071273804,-56568542383.59514,1744061312.6951218,7.061464071273804,0.065,1744061312.6951234,7.061464071273804,3.1415926535823155,1744061312.695125,7.061464071273804,0.4230023959247359,1744061312.695126,7.061464071273804,6.091234525300619e-22,1744061312.6951272,7.061464071273804,1.7822717509233952,1744061312.6951292,7.061464071273804,0.0,1744061312.69513,7.061464071273804,-22627416996.543705,1744061312.695131,7.061464071273804,0.0,1744061312.6951323,7.061464071273804,28284271247.461903
+1744061312.7146854,7.081484794616699,-0.04151747484243354,1744061312.7146873,7.081484794616699,-0.3580044463077798,1744061312.7146893,7.081484794616699,0.0013530044463077797,1744061312.7146914,7.081484794616699,-56568542383.59514,1744061312.7146924,7.081484794616699,0.065,1744061312.7146935,7.081484794616699,3.1415926535823155,1744061312.7146947,7.081484794616699,0.4230023959247359,1744061312.7146957,7.081484794616699,6.091234525300619e-22,1744061312.7146964,7.081484794616699,1.7822717509233952,1744061312.714698,7.081484794616699,0.0,1744061312.714699,7.081484794616699,-22627416996.543705,1744061312.7147,7.081484794616699,0.0,1744061312.714701,7.081484794616699,28284271247.461903
+1744061312.7350352,7.101467847824097,-0.04151747484243354,1744061312.7350366,7.101467847824097,-0.3580044463077798,1744061312.7350388,7.101467847824097,0.0013530044463077797,1744061312.7350407,7.101467847824097,-56568542383.59514,1744061312.735042,7.101467847824097,0.065,1744061312.7350433,7.101467847824097,3.1415926535823155,1744061312.7350442,7.101467847824097,0.4230023959247359,1744061312.7350454,7.101467847824097,6.091234525300619e-22,1744061312.7350461,7.101467847824097,1.7822717509233952,1744061312.7350473,7.101467847824097,0.0,1744061312.7350485,7.101467847824097,-22627416996.543705,1744061312.7350495,7.101467847824097,0.0,1744061312.7350504,7.101467847824097,28284271247.461903
+1744061312.7552865,7.12148642539978,-0.04151747484243354,1744061312.7552898,7.12148642539978,-0.3580044463077798,1744061312.7552927,7.12148642539978,0.0013530044463077797,1744061312.7552953,7.12148642539978,-56568542383.59514,1744061312.7552972,7.12148642539978,0.065,1744061312.755299,7.12148642539978,3.1415926535823155,1744061312.7553008,7.12148642539978,0.4230023959247359,1744061312.7553022,7.12148642539978,6.091234525300619e-22,1744061312.7553034,7.12148642539978,1.7822717509233952,1744061312.755306,7.12148642539978,0.0,1744061312.755307,7.12148642539978,-22627416996.543705,1744061312.7553084,7.12148642539978,0.0,1744061312.7553093,7.12148642539978,28284271247.461903
+1744061312.7747743,7.141479253768921,-0.04151747484243354,1744061312.774776,7.141479253768921,-0.3580044463077798,1744061312.7747784,7.141479253768921,0.0013530044463077797,1744061312.7747805,7.141479253768921,-56568542383.59514,1744061312.7747817,7.141479253768921,0.065,1744061312.7747834,7.141479253768921,3.1415926535823155,1744061312.7747843,7.141479253768921,0.4230023959247359,1744061312.7747853,7.141479253768921,6.091234525300619e-22,1744061312.7747862,7.141479253768921,1.7822717509233952,1744061312.774788,7.141479253768921,0.0,1744061312.7747889,7.141479253768921,-22627416996.543705,1744061312.77479,7.141479253768921,0.0,1744061312.774791,7.141479253768921,28284271247.461903
+1744061312.7949078,7.1614463329315186,-0.04151747484243354,1744061312.79491,7.1614463329315186,-0.3580044463077798,1744061312.7949123,7.1614463329315186,0.0013530044463077797,1744061312.7949142,7.1614463329315186,-56568542383.59514,1744061312.7949157,7.1614463329315186,0.065,1744061312.7949169,7.1614463329315186,3.1415926535823155,1744061312.794918,7.1614463329315186,0.4230023959247359,1744061312.794919,7.1614463329315186,6.091234525300619e-22,1744061312.7949202,7.1614463329315186,1.7822717509233952,1744061312.7949216,7.1614463329315186,0.0,1744061312.7949228,7.1614463329315186,-22627416996.543705,1744061312.794924,7.1614463329315186,0.0,1744061312.794925,7.1614463329315186,28284271247.461903
+1744061312.8148007,7.181484222412109,-0.04151747484243354,1744061312.8148031,7.181484222412109,-0.3580044463077798,1744061312.8148062,7.181484222412109,0.0013530044463077797,1744061312.814809,7.181484222412109,-56568542383.59514,1744061312.8148105,7.181484222412109,0.065,1744061312.8148124,7.181484222412109,3.1415926535823155,1744061312.8148139,7.181484222412109,0.4230023959247359,1744061312.8148155,7.181484222412109,6.091234525300619e-22,1744061312.8148167,7.181484222412109,1.7822717509233952,1744061312.8148186,7.181484222412109,0.0,1744061312.81482,7.181484222412109,-22627416996.543705,1744061312.8148215,7.181484222412109,0.0,1744061312.8148232,7.181484222412109,28284271247.461903
+1744061312.8352828,7.20147442817688,-0.22680291068227285,1744061312.835304,7.20147442817688,-1.183255177911879,1744061312.8353062,7.20147442817688,0.011304960386114305,1744061312.8353083,7.20147442817688,-56568542383.605095,1744061312.8353093,7.20147442817688,0.065,1744061312.8353107,7.20147442817688,3.141592653567727,1744061312.8353121,7.20147442817688,1.2482429905803543,1744061312.8353128,7.20147442817688,1.797469913524445e-21,1744061312.835314,7.20147442817688,0.9209922471805334,1744061312.8353152,7.20147442817688,0.0,1744061312.835316,7.20147442817688,-22627416997.232727,1744061312.8353171,7.20147442817688,0.0,1744061312.835318,7.20147442817688,28284271247.461903
+1744061312.856427,7.221556186676025,-0.22680291068227285,1744061312.8564332,7.221556186676025,-1.183255177911879,1744061312.8564415,7.221556186676025,0.011304960386114305,1744061312.8564515,7.221556186676025,-56568542383.605095,1744061312.856455,7.221556186676025,0.065,1744061312.8564625,7.221556186676025,3.141592653567727,1744061312.8564703,7.221556186676025,1.2482429905803543,1744061312.8564768,7.221556186676025,1.797469913524445e-21,1744061312.8564794,7.221556186676025,0.9209922471805334,1744061312.856484,7.221556186676025,0.0,1744061312.8564863,7.221556186676025,-22627416997.232727,1744061312.8564894,7.221556186676025,0.0,1744061312.8564916,7.221556186676025,28284271247.461903
+1744061312.8747466,7.241455793380737,-0.22680291068227285,1744061312.8747487,7.241455793380737,-1.183255177911879,1744061312.874751,7.241455793380737,0.011304960386114305,1744061312.874753,7.241455793380737,-56568542383.605095,1744061312.874754,7.241455793380737,0.065,1744061312.8747556,7.241455793380737,3.141592653567727,1744061312.8747566,7.241455793380737,1.2482429905803543,1744061312.8747573,7.241455793380737,1.797469913524445e-21,1744061312.8747585,7.241455793380737,0.9209922471805334,1744061312.87476,7.241455793380737,0.0,1744061312.8747606,7.241455793380737,-22627416997.232727,1744061312.8747618,7.241455793380737,0.0,1744061312.8747628,7.241455793380737,28284271247.461903
+1744061312.8950834,7.261476278305054,-0.22680291068227285,1744061312.895086,7.261476278305054,-1.183255177911879,1744061312.895108,7.261476278305054,0.011304960386114305,1744061312.8951106,7.261476278305054,-56568542383.605095,1744061312.8951123,7.261476278305054,0.065,1744061312.8951137,7.261476278305054,3.141592653567727,1744061312.8951154,7.261476278305054,1.2482429905803543,1744061312.8951352,7.261476278305054,1.797469913524445e-21,1744061312.8951368,7.261476278305054,0.9209922471805334,1744061312.8951397,7.261476278305054,0.0,1744061312.8951414,7.261476278305054,-22627416997.232727,1744061312.8951423,7.261476278305054,0.0,1744061312.8951437,7.261476278305054,28284271247.461903
+1744061312.9146557,7.281446695327759,-0.22680291068227285,1744061312.9146578,7.281446695327759,-1.183255177911879,1744061312.9146597,7.281446695327759,0.011304960386114305,1744061312.914662,7.281446695327759,-56568542383.605095,1744061312.914663,7.281446695327759,0.065,1744061312.9146643,7.281446695327759,3.141592653567727,1744061312.9146652,7.281446695327759,1.2482429905803543,1744061312.9146662,7.281446695327759,1.797469913524445e-21,1744061312.9146674,7.281446695327759,0.9209922471805334,1744061312.9146686,7.281446695327759,0.0,1744061312.9146693,7.281446695327759,-22627416997.232727,1744061312.9146702,7.281446695327759,0.0,1744061312.9146714,7.281446695327759,28284271247.461903
+1744061312.934952,7.3014514446258545,-0.22680291068227285,1744061312.9349535,7.3014514446258545,-1.183255177911879,1744061312.9349558,7.3014514446258545,0.011304960386114305,1744061312.9349575,7.3014514446258545,-56568542383.605095,1744061312.934959,7.3014514446258545,0.065,1744061312.9349601,7.3014514446258545,3.141592653567727,1744061312.934961,7.3014514446258545,1.2482429905803543,1744061312.934962,7.3014514446258545,1.797469913524445e-21,1744061312.934963,7.3014514446258545,0.9209922471805334,1744061312.934964,7.3014514446258545,0.0,1744061312.934965,7.3014514446258545,-22627416997.232727,1744061312.934966,7.3014514446258545,0.0,1744061312.934967,7.3014514446258545,28284271247.461903
+1744061312.954813,7.321474552154541,-0.22680291068227285,1744061312.954815,7.321474552154541,-1.183255177911879,1744061312.9548173,7.321474552154541,0.011304960386114305,1744061312.9548197,7.321474552154541,-56568542383.605095,1744061312.9548206,7.321474552154541,0.065,1744061312.9548218,7.321474552154541,3.141592653567727,1744061312.9548233,7.321474552154541,1.2482429905803543,1744061312.954824,7.321474552154541,1.797469913524445e-21,1744061312.954825,7.321474552154541,0.9209922471805334,1744061312.9548266,7.321474552154541,0.0,1744061312.9548278,7.321474552154541,-22627416997.232727,1744061312.9548287,7.321474552154541,0.0,1744061312.95483,7.321474552154541,28284271247.461903
+1744061312.9747508,7.341454267501831,-0.22680291068227285,1744061312.9747522,7.341454267501831,-1.183255177911879,1744061312.9747546,7.341454267501831,0.011304960386114305,1744061312.974757,7.341454267501831,-56568542383.605095,1744061312.9747581,7.341454267501831,0.065,1744061312.9747596,7.341454267501831,3.141592653567727,1744061312.9747608,7.341454267501831,1.2482429905803543,1744061312.9747617,7.341454267501831,1.797469913524445e-21,1744061312.9747627,7.341454267501831,0.9209922471805334,1744061312.9747643,7.341454267501831,0.0,1744061312.974765,7.341454267501831,-22627416997.232727,1744061312.9747663,7.341454267501831,0.0,1744061312.9747674,7.341454267501831,28284271247.461903
+1744061312.9950492,7.361451864242554,-0.22680291068227285,1744061312.9950519,7.361451864242554,-1.183255177911879,1744061312.9950542,7.361451864242554,0.011304960386114305,1744061312.9950564,7.361451864242554,-56568542383.605095,1744061312.9950576,7.361451864242554,0.065,1744061312.995059,7.361451864242554,3.141592653567727,1744061312.99506,7.361451864242554,1.2482429905803543,1744061312.995061,7.361451864242554,1.797469913524445e-21,1744061312.995062,7.361451864242554,0.9209922471805334,1744061312.9950635,7.361451864242554,0.0,1744061312.9950647,7.361451864242554,-22627416997.232727,1744061312.9950657,7.361451864242554,0.0,1744061312.9950666,7.361451864242554,28284271247.461903
+1744061313.0147164,7.381457805633545,-0.22680291068227285,1744061313.0147183,7.381457805633545,-1.183255177911879,1744061313.0147204,7.381457805633545,0.011304960386114305,1744061313.0147226,7.381457805633545,-56568542383.605095,1744061313.0147238,7.381457805633545,0.065,1744061313.0147252,7.381457805633545,3.141592653567727,1744061313.0147264,7.381457805633545,1.2482429905803543,1744061313.014727,7.381457805633545,1.797469913524445e-21,1744061313.0147283,7.381457805633545,0.9209922471805334,1744061313.0147297,7.381457805633545,0.0,1744061313.0147307,7.381457805633545,-22627416997.232727,1744061313.014732,7.381457805633545,0.0,1744061313.0147328,7.381457805633545,28284271247.461903
+1744061313.035005,7.4014739990234375,-0.22680291068227285,1744061313.035008,7.4014739990234375,-1.183255177911879,1744061313.0350113,7.4014739990234375,0.011304960386114305,1744061313.0350146,7.4014739990234375,-56568542383.605095,1744061313.0350165,7.4014739990234375,0.065,1744061313.035018,7.4014739990234375,3.141592653567727,1744061313.035019,7.4014739990234375,1.2482429905803543,1744061313.0350199,7.4014739990234375,1.797469913524445e-21,1744061313.0350208,7.4014739990234375,0.9209922471805334,1744061313.0350223,7.4014739990234375,0.0,1744061313.0350235,7.4014739990234375,-22627416997.232727,1744061313.0350242,7.4014739990234375,0.0,1744061313.0350251,7.4014739990234375,28284271247.461903
+1744061313.0547981,7.421459674835205,-0.22680291068227285,1744061313.0548,7.421459674835205,-1.183255177911879,1744061313.0548024,7.421459674835205,0.011304960386114305,1744061313.0548046,7.421459674835205,-56568542383.605095,1744061313.0548058,7.421459674835205,0.065,1744061313.054807,7.421459674835205,3.141592653567727,1744061313.0548084,7.421459674835205,1.2482429905803543,1744061313.054809,7.421459674835205,1.797469913524445e-21,1744061313.05481,7.421459674835205,0.9209922471805334,1744061313.0548115,7.421459674835205,0.0,1744061313.0548124,7.421459674835205,-22627416997.232727,1744061313.0548136,7.421459674835205,0.0,1744061313.0548146,7.421459674835205,28284271247.461903
+1744061313.0746634,7.441446542739868,-0.22680291068227285,1744061313.0746665,7.441446542739868,-1.183255177911879,1744061313.0746698,7.441446542739868,0.011304960386114305,1744061313.0746725,7.441446542739868,-56568542383.605095,1744061313.0746737,7.441446542739868,0.065,1744061313.0746748,7.441446542739868,3.141592653567727,1744061313.074676,7.441446542739868,1.2482429905803543,1744061313.074677,7.441446542739868,1.797469913524445e-21,1744061313.0746777,7.441446542739868,0.9209922471805334,1744061313.0746794,7.441446542739868,0.0,1744061313.0746803,7.441446542739868,-22627416997.232727,1744061313.0746813,7.441446542739868,0.0,1744061313.0746825,7.441446542739868,28284271247.461903
+1744061313.0949519,7.4614551067352295,-0.22680291068227285,1744061313.094954,7.4614551067352295,-1.183255177911879,1744061313.0949564,7.4614551067352295,0.011304960386114305,1744061313.0949583,7.4614551067352295,-56568542383.605095,1744061313.0949593,7.4614551067352295,0.065,1744061313.0949607,7.4614551067352295,3.141592653567727,1744061313.0949616,7.4614551067352295,1.2482429905803543,1744061313.0949626,7.4614551067352295,1.797469913524445e-21,1744061313.0949638,7.4614551067352295,0.9209922471805334,1744061313.094965,7.4614551067352295,0.0,1744061313.094966,7.4614551067352295,-22627416997.232727,1744061313.0949671,7.4614551067352295,0.0,1744061313.094968,7.4614551067352295,28284271247.461903
+1744061313.114722,7.481469631195068,-0.22680291068227285,1744061313.114724,7.481469631195068,-1.183255177911879,1744061313.1147258,7.481469631195068,0.011304960386114305,1744061313.114728,7.481469631195068,-56568542383.605095,1744061313.114729,7.481469631195068,0.065,1744061313.1147304,7.481469631195068,3.141592653567727,1744061313.1147313,7.481469631195068,1.2482429905803543,1744061313.1147323,7.481469631195068,1.797469913524445e-21,1744061313.1147332,7.481469631195068,0.9209922471805334,1744061313.1147346,7.481469631195068,0.0,1744061313.1147356,7.481469631195068,-22627416997.232727,1744061313.1147368,7.481469631195068,0.0,1744061313.114738,7.481469631195068,28284271247.461903
+1744061313.1357708,7.501510143280029,-0.22680291068227285,1744061313.1357744,7.501510143280029,-1.183255177911879,1744061313.135778,7.501510143280029,0.011304960386114305,1744061313.1357808,7.501510143280029,-56568542383.605095,1744061313.1357827,7.501510143280029,0.065,1744061313.1357849,7.501510143280029,3.141592653567727,1744061313.1357868,7.501510143280029,1.2482429905803543,1744061313.1357877,7.501510143280029,1.797469913524445e-21,1744061313.1357899,7.501510143280029,0.9209922471805334,1744061313.135792,7.501510143280029,0.0,1744061313.1357932,7.501510143280029,-22627416997.232727,1744061313.1357954,7.501510143280029,0.0,1744061313.1357975,7.501510143280029,28284271247.461903
+1744061313.155212,7.521482706069946,-0.22680291068227285,1744061313.1552143,7.521482706069946,-1.183255177911879,1744061313.1552174,7.521482706069946,0.011304960386114305,1744061313.1552198,7.521482706069946,-56568542383.605095,1744061313.1552217,7.521482706069946,0.065,1744061313.1552253,7.521482706069946,3.141592653567727,1744061313.1552281,7.521482706069946,1.2482429905803543,1744061313.1552298,7.521482706069946,1.797469913524445e-21,1744061313.1552315,7.521482706069946,0.9209922471805334,1744061313.1552355,7.521482706069946,0.0,1744061313.155237,7.521482706069946,-22627416997.232727,1744061313.155239,7.521482706069946,0.0,1744061313.1552413,7.521482706069946,28284271247.461903
+1744061313.1750724,7.541484117507935,-0.22680291068227285,1744061313.1750746,7.541484117507935,-1.183255177911879,1744061313.1750767,7.541484117507935,0.011304960386114305,1744061313.1750786,7.541484117507935,-56568542383.605095,1744061313.1750796,7.541484117507935,0.065,1744061313.175081,7.541484117507935,3.141592653567727,1744061313.1750822,7.541484117507935,1.2482429905803543,1744061313.175083,7.541484117507935,1.797469913524445e-21,1744061313.175084,7.541484117507935,0.9209922471805334,1744061313.1750855,7.541484117507935,0.0,1744061313.1750865,7.541484117507935,-22627416997.232727,1744061313.1750877,7.541484117507935,0.0,1744061313.1750886,7.541484117507935,28284271247.461903
+1744061313.195186,7.561474323272705,-0.22680291068227285,1744061313.1951883,7.561474323272705,-1.183255177911879,1744061313.1951916,7.561474323272705,0.011304960386114305,1744061313.1951945,7.561474323272705,-56568542383.605095,1744061313.1951962,7.561474323272705,0.065,1744061313.1951983,7.561474323272705,3.141592653567727,1744061313.1952,7.561474323272705,1.2482429905803543,1744061313.1952014,7.561474323272705,1.797469913524445e-21,1744061313.1952035,7.561474323272705,0.9209922471805334,1744061313.1952062,7.561474323272705,0.0,1744061313.1952078,7.561474323272705,-22627416997.232727,1744061313.1952095,7.561474323272705,0.0,1744061313.1952114,7.561474323272705,28284271247.461903
+1744061313.2148778,7.581489324569702,-0.22680291068227285,1744061313.2148805,7.581489324569702,-1.183255177911879,1744061313.2148833,7.581489324569702,0.011304960386114305,1744061313.214886,7.581489324569702,-56568542383.605095,1744061313.2148871,7.581489324569702,0.065,1744061313.2148888,7.581489324569702,3.141592653567727,1744061313.2148902,7.581489324569702,1.2482429905803543,1744061313.2148912,7.581489324569702,1.797469913524445e-21,1744061313.2148926,7.581489324569702,0.9209922471805334,1744061313.2148943,7.581489324569702,0.0,1744061313.2148957,7.581489324569702,-22627416997.232727,1744061313.214897,7.581489324569702,0.0,1744061313.214898,7.581489324569702,28284271247.461903
+1744061313.2353356,7.601455211639404,-0.22680291068227285,1744061313.235338,7.601455211639404,-1.183255177911879,1744061313.235341,7.601455211639404,0.011304960386114305,1744061313.2353437,7.601455211639404,-56568542383.605095,1744061313.235345,7.601455211639404,0.065,1744061313.2353468,7.601455211639404,3.141592653567727,1744061313.2353482,7.601455211639404,1.2482429905803543,1744061313.2353492,7.601455211639404,1.797469913524445e-21,1744061313.2353506,7.601455211639404,0.9209922471805334,1744061313.2353523,7.601455211639404,0.0,1744061313.2353537,7.601455211639404,-22627416997.232727,1744061313.2353551,7.601455211639404,0.0,1744061313.2353563,7.601455211639404,28284271247.461903
+1744061313.254915,7.621463298797607,-0.22680291068227285,1744061313.2549176,7.621463298797607,-1.183255177911879,1744061313.2549205,7.621463298797607,0.011304960386114305,1744061313.2549233,7.621463298797607,-56568542383.605095,1744061313.2549248,7.621463298797607,0.065,1744061313.2549267,7.621463298797607,3.141592653567727,1744061313.2549279,7.621463298797607,1.2482429905803543,1744061313.254929,7.621463298797607,1.797469913524445e-21,1744061313.2549307,7.621463298797607,0.9209922471805334,1744061313.2549324,7.621463298797607,0.0,1744061313.2549338,7.621463298797607,-22627416997.232727,1744061313.2549353,7.621463298797607,0.0,1744061313.254937,7.621463298797607,28284271247.461903
+1744061313.2749472,7.641486167907715,-0.22680291068227285,1744061313.2749493,7.641486167907715,-1.183255177911879,1744061313.2749522,7.641486167907715,0.011304960386114305,1744061313.2749548,7.641486167907715,-56568542383.605095,1744061313.2749562,7.641486167907715,0.065,1744061313.274958,7.641486167907715,3.141592653567727,1744061313.2749593,7.641486167907715,1.2482429905803543,1744061313.2749603,7.641486167907715,1.797469913524445e-21,1744061313.2749617,7.641486167907715,0.9209922471805334,1744061313.2749634,7.641486167907715,0.0,1744061313.2749648,7.641486167907715,-22627416997.232727,1744061313.2749662,7.641486167907715,0.0,1744061313.2749677,7.641486167907715,28284271247.461903
+1744061313.294886,7.661463975906372,-0.22680291068227285,1744061313.2948887,7.661463975906372,-1.183255177911879,1744061313.2948916,7.661463975906372,0.011304960386114305,1744061313.2948942,7.661463975906372,-56568542383.605095,1744061313.2948956,7.661463975906372,0.065,1744061313.294897,7.661463975906372,3.141592653567727,1744061313.2948987,7.661463975906372,1.2482429905803543,1744061313.2949,7.661463975906372,1.797469913524445e-21,1744061313.2949011,7.661463975906372,0.9209922471805334,1744061313.2949028,7.661463975906372,0.0,1744061313.294904,7.661463975906372,-22627416997.232727,1744061313.2949054,7.661463975906372,0.0,1744061313.2949066,7.661463975906372,28284271247.461903
+1744061313.3151364,7.68146538734436,-0.22680291068227285,1744061313.3151393,7.68146538734436,-1.183255177911879,1744061313.3151429,7.68146538734436,0.011304960386114305,1744061313.3151457,7.68146538734436,-56568542383.605095,1744061313.3151476,7.68146538734436,0.065,1744061313.3151493,7.68146538734436,3.141592653567727,1744061313.3151515,7.68146538734436,1.2482429905803543,1744061313.3151526,7.68146538734436,1.797469913524445e-21,1744061313.315154,7.68146538734436,0.9209922471805334,1744061313.3151562,7.68146538734436,0.0,1744061313.3151577,7.68146538734436,-22627416997.232727,1744061313.3151593,7.68146538734436,0.0,1744061313.3151608,7.68146538734436,28284271247.461903
+1744061313.3354392,7.701500415802002,-0.528006175937269,1744061313.3354414,7.701500415802002,-2.5562180491147086,1744061313.3354445,7.701500415802002,0.000530006175937269,1744061313.335447,7.701500415802002,-56568542383.594315,1744061313.3354485,7.701500415802002,0.065,1744061313.3354502,7.701500415802002,3.1415926535434564,1744061313.3354516,7.701500415802002,2.621207198169708,1744061313.3354526,7.701500415802002,3.7745383802917715e-21,1744061313.335454,7.701500415802002,0.3070713872517473,1744061313.3354554,7.701500415802002,0.0,1744061313.3354568,7.701500415802002,-22627416997.723866,1744061313.335458,7.701500415802002,0.0,1744061313.3354592,7.701500415802002,28284271247.461903
+1744061313.35549,7.721502780914307,-0.528006175937269,1744061313.355493,7.721502780914307,-2.5562180491147086,1744061313.3554964,7.721502780914307,0.000530006175937269,1744061313.3554993,7.721502780914307,-56568542383.594315,1744061313.3555005,7.721502780914307,0.065,1744061313.3555028,7.721502780914307,3.1415926535434564,1744061313.3555048,7.721502780914307,2.621207198169708,1744061313.3555062,7.721502780914307,3.7745383802917715e-21,1744061313.3555074,7.721502780914307,0.3070713872517473,1744061313.3555098,7.721502780914307,0.0,1744061313.3555107,7.721502780914307,-22627416997.723866,1744061313.3555124,7.721502780914307,0.0,1744061313.3555136,7.721502780914307,28284271247.461903
+1744061313.3750331,7.741467714309692,-0.528006175937269,1744061313.3750353,7.741467714309692,-2.5562180491147086,1744061313.3750381,7.741467714309692,0.000530006175937269,1744061313.375041,7.741467714309692,-56568542383.594315,1744061313.3750422,7.741467714309692,0.065,1744061313.3750443,7.741467714309692,3.1415926535434564,1744061313.3750458,7.741467714309692,2.621207198169708,1744061313.3750472,7.741467714309692,3.7745383802917715e-21,1744061313.3750484,7.741467714309692,0.3070713872517473,1744061313.3750503,7.741467714309692,0.0,1744061313.3750517,7.741467714309692,-22627416997.723866,1744061313.3750532,7.741467714309692,0.0,1744061313.3750544,7.741467714309692,28284271247.461903
+1744061313.3949094,7.761460542678833,-0.528006175937269,1744061313.3949122,7.761460542678833,-2.5562180491147086,1744061313.394915,7.761460542678833,0.000530006175937269,1744061313.394918,7.761460542678833,-56568542383.594315,1744061313.3949194,7.761460542678833,0.065,1744061313.394921,7.761460542678833,3.1415926535434564,1744061313.3949225,7.761460542678833,2.621207198169708,1744061313.3949237,7.761460542678833,3.7745383802917715e-21,1744061313.3949249,7.761460542678833,0.3070713872517473,1744061313.3949265,7.761460542678833,0.0,1744061313.394928,7.761460542678833,-22627416997.723866,1744061313.3949292,7.761460542678833,0.0,1744061313.3949304,7.761460542678833,28284271247.461903
+1744061313.4149137,7.781453371047974,-0.528006175937269,1744061313.4149184,7.781453371047974,-2.5562180491147086,1744061313.4149225,7.781453371047974,0.000530006175937269,1744061313.4149256,7.781453371047974,-56568542383.594315,1744061313.414927,7.781453371047974,0.065,1744061313.414929,7.781453371047974,3.1415926535434564,1744061313.4149303,7.781453371047974,2.621207198169708,1744061313.4149315,7.781453371047974,3.7745383802917715e-21,1744061313.414933,7.781453371047974,0.3070713872517473,1744061313.4149349,7.781453371047974,0.0,1744061313.414936,7.781453371047974,-22627416997.723866,1744061313.4149375,7.781453371047974,0.0,1744061313.414939,7.781453371047974,28284271247.461903
+1744061313.4351115,7.80144739151001,-0.528006175937269,1744061313.435114,7.80144739151001,-2.5562180491147086,1744061313.4351168,7.80144739151001,0.000530006175937269,1744061313.4351196,7.80144739151001,-56568542383.594315,1744061313.4351208,7.80144739151001,0.065,1744061313.4351227,7.80144739151001,3.1415926535434564,1744061313.435124,7.80144739151001,2.621207198169708,1744061313.4351254,7.80144739151001,3.7745383802917715e-21,1744061313.4351265,7.80144739151001,0.3070713872517473,1744061313.435128,7.80144739151001,0.0,1744061313.4351294,7.80144739151001,-22627416997.723866,1744061313.4351306,7.80144739151001,0.0,1744061313.4351318,7.80144739151001,28284271247.461903
+1744061313.4552777,7.821494102478027,-0.528006175937269,1744061313.4552822,7.821494102478027,-2.5562180491147086,1744061313.4552865,7.821494102478027,0.000530006175937269,1744061313.4552908,7.821494102478027,-56568542383.594315,1744061313.4552927,7.821494102478027,0.065,1744061313.4552944,7.821494102478027,3.1415926535434564,1744061313.4552965,7.821494102478027,2.621207198169708,1744061313.4552975,7.821494102478027,3.7745383802917715e-21,1744061313.4552991,7.821494102478027,0.3070713872517473,1744061313.455302,7.821494102478027,0.0,1744061313.4553037,7.821494102478027,-22627416997.723866,1744061313.455305,7.821494102478027,0.0,1744061313.4553065,7.821494102478027,28284271247.461903
+1744061313.474903,7.841461420059204,-0.528006175937269,1744061313.4749053,7.841461420059204,-2.5562180491147086,1744061313.474908,7.841461420059204,0.000530006175937269,1744061313.474911,7.841461420059204,-56568542383.594315,1744061313.4749122,7.841461420059204,0.065,1744061313.4749138,7.841461420059204,3.1415926535434564,1744061313.4749153,7.841461420059204,2.621207198169708,1744061313.4749167,7.841461420059204,3.7745383802917715e-21,1744061313.474918,7.841461420059204,0.3070713872517473,1744061313.4749198,7.841461420059204,0.0,1744061313.474921,7.841461420059204,-22627416997.723866,1744061313.4749222,7.841461420059204,0.0,1744061313.4749236,7.841461420059204,28284271247.461903
+1744061313.4948363,7.861446857452393,-0.528006175937269,1744061313.4948385,7.861446857452393,-2.5562180491147086,1744061313.4948413,7.861446857452393,0.000530006175937269,1744061313.4948442,7.861446857452393,-56568542383.594315,1744061313.4948454,7.861446857452393,0.065,1744061313.494847,7.861446857452393,3.1415926535434564,1744061313.4948485,7.861446857452393,2.621207198169708,1744061313.4948497,7.861446857452393,3.7745383802917715e-21,1744061313.494851,7.861446857452393,0.3070713872517473,1744061313.4948528,7.861446857452393,0.0,1744061313.494855,7.861446857452393,-22627416997.723866,1744061313.494857,7.861446857452393,0.0,1744061313.494859,7.861446857452393,28284271247.461903
+1744061313.514822,7.881448268890381,-0.528006175937269,1744061313.5148244,7.881448268890381,-2.5562180491147086,1744061313.5148273,7.881448268890381,0.000530006175937269,1744061313.5148299,7.881448268890381,-56568542383.594315,1744061313.5148313,7.881448268890381,0.065,1744061313.514833,7.881448268890381,3.1415926535434564,1744061313.5148342,7.881448268890381,2.621207198169708,1744061313.5148354,7.881448268890381,3.7745383802917715e-21,1744061313.5148365,7.881448268890381,0.3070713872517473,1744061313.5148382,7.881448268890381,0.0,1744061313.5148396,7.881448268890381,-22627416997.723866,1744061313.5148408,7.881448268890381,0.0,1744061313.514842,7.881448268890381,28284271247.461903
+1744061313.535614,7.901447772979736,-0.528006175937269,1744061313.5356164,7.901447772979736,-2.5562180491147086,1744061313.5356193,7.901447772979736,0.000530006175937269,1744061313.5356221,7.901447772979736,-56568542383.594315,1744061313.5356233,7.901447772979736,0.065,1744061313.5356252,7.901447772979736,3.1415926535434564,1744061313.5356266,7.901447772979736,2.621207198169708,1744061313.5356278,7.901447772979736,3.7745383802917715e-21,1744061313.5356293,7.901447772979736,0.3070713872517473,1744061313.5356312,7.901447772979736,0.0,1744061313.5356324,7.901447772979736,-22627416997.723866,1744061313.5356338,7.901447772979736,0.0,1744061313.5356352,7.901447772979736,28284271247.461903
+1744061313.5554123,7.921502351760864,-0.528006175937269,1744061313.5554147,7.921502351760864,-2.5562180491147086,1744061313.5554175,7.921502351760864,0.000530006175937269,1744061313.5554204,7.921502351760864,-56568542383.594315,1744061313.5554216,7.921502351760864,0.065,1744061313.5554235,7.921502351760864,3.1415926535434564,1744061313.5554252,7.921502351760864,2.621207198169708,1744061313.5554264,7.921502351760864,3.7745383802917715e-21,1744061313.5554276,7.921502351760864,0.3070713872517473,1744061313.5554297,7.921502351760864,0.0,1744061313.555431,7.921502351760864,-22627416997.723866,1744061313.555432,7.921502351760864,0.0,1744061313.5554335,7.921502351760864,28284271247.461903
+1744061313.574909,7.94144868850708,-0.528006175937269,1744061313.5749116,7.94144868850708,-2.5562180491147086,1744061313.5749142,7.94144868850708,0.000530006175937269,1744061313.5749207,7.94144868850708,-56568542383.594315,1744061313.5749223,7.94144868850708,0.065,1744061313.574924,7.94144868850708,3.1415926535434564,1744061313.5749254,7.94144868850708,2.621207198169708,1744061313.5749269,7.94144868850708,3.7745383802917715e-21,1744061313.574928,7.94144868850708,0.3070713872517473,1744061313.5749297,7.94144868850708,0.0,1744061313.574931,7.94144868850708,-22627416997.723866,1744061313.5749326,7.94144868850708,0.0,1744061313.5749338,7.94144868850708,28284271247.461903
+1744061313.5951035,7.96148943901062,-0.528006175937269,1744061313.5951061,7.96148943901062,-2.5562180491147086,1744061313.5951095,7.96148943901062,0.000530006175937269,1744061313.595112,7.96148943901062,-56568542383.594315,1744061313.595114,7.96148943901062,0.065,1744061313.5951161,7.96148943901062,3.1415926535434564,1744061313.5951176,7.96148943901062,2.621207198169708,1744061313.5951188,7.96148943901062,3.7745383802917715e-21,1744061313.5951202,7.96148943901062,0.3070713872517473,1744061313.5951219,7.96148943901062,0.0,1744061313.5951233,7.96148943901062,-22627416997.723866,1744061313.595125,7.96148943901062,0.0,1744061313.5951264,7.96148943901062,28284271247.461903
+1744061313.614872,7.981454610824585,-0.528006175937269,1744061313.6148744,7.981454610824585,-2.5562180491147086,1744061313.6148775,7.981454610824585,0.000530006175937269,1744061313.61488,7.981454610824585,-56568542383.594315,1744061313.6148815,7.981454610824585,0.065,1744061313.6148832,7.981454610824585,3.1415926535434564,1744061313.6148846,7.981454610824585,2.621207198169708,1744061313.6148856,7.981454610824585,3.7745383802917715e-21,1744061313.614887,7.981454610824585,0.3070713872517473,1744061313.6148887,7.981454610824585,0.0,1744061313.61489,7.981454610824585,-22627416997.723866,1744061313.6148915,7.981454610824585,0.0,1744061313.6148927,7.981454610824585,28284271247.461903
+1744061313.6352067,8.001450777053833,-0.528006175937269,1744061313.6352093,8.001450777053833,-2.5562180491147086,1744061313.6352117,8.001450777053833,0.000530006175937269,1744061313.6352143,8.001450777053833,-56568542383.594315,1744061313.6352158,8.001450777053833,0.065,1744061313.6352174,8.001450777053833,3.1415926535434564,1744061313.6352186,8.001450777053833,2.621207198169708,1744061313.63522,8.001450777053833,3.7745383802917715e-21,1744061313.6352212,8.001450777053833,0.3070713872517473,1744061313.6352227,8.001450777053833,0.0,1744061313.635224,8.001450777053833,-22627416997.723866,1744061313.6352253,8.001450777053833,0.0,1744061313.6352267,8.001450777053833,28284271247.461903
+1744061313.6548996,8.021464347839355,-0.528006175937269,1744061313.654902,8.021464347839355,-2.5562180491147086,1744061313.6549048,8.021464347839355,0.000530006175937269,1744061313.6549077,8.021464347839355,-56568542383.594315,1744061313.654909,8.021464347839355,0.065,1744061313.6549108,8.021464347839355,3.1415926535434564,1744061313.6549122,8.021464347839355,2.621207198169708,1744061313.6549132,8.021464347839355,3.7745383802917715e-21,1744061313.6549146,8.021464347839355,0.3070713872517473,1744061313.6549165,8.021464347839355,0.0,1744061313.6549182,8.021464347839355,-22627416997.723866,1744061313.6549196,8.021464347839355,0.0,1744061313.654921,8.021464347839355,28284271247.461903
+1744061313.674908,8.041448831558228,-0.528006175937269,1744061313.6749108,8.041448831558228,-2.5562180491147086,1744061313.6749141,8.041448831558228,0.000530006175937269,1744061313.674917,8.041448831558228,-56568542383.594315,1744061313.6749182,8.041448831558228,0.065,1744061313.6749196,8.041448831558228,3.1415926535434564,1744061313.6749213,8.041448831558228,2.621207198169708,1744061313.6749225,8.041448831558228,3.7745383802917715e-21,1744061313.6749237,8.041448831558228,0.3070713872517473,1744061313.6749256,8.041448831558228,0.0,1744061313.6749268,8.041448831558228,-22627416997.723866,1744061313.6749284,8.041448831558228,0.0,1744061313.6749296,8.041448831558228,28284271247.461903
+1744061313.695008,8.061453819274902,-0.528006175937269,1744061313.6950119,8.061453819274902,-2.5562180491147086,1744061313.6950154,8.061453819274902,0.000530006175937269,1744061313.6950183,8.061453819274902,-56568542383.594315,1744061313.6950202,8.061453819274902,0.065,1744061313.6950226,8.061453819274902,3.1415926535434564,1744061313.695024,8.061453819274902,2.621207198169708,1744061313.6950254,8.061453819274902,3.7745383802917715e-21,1744061313.695027,8.061453819274902,0.3070713872517473,1744061313.69503,8.061453819274902,0.0,1744061313.695032,8.061453819274902,-22627416997.723866,1744061313.6950336,8.061453819274902,0.0,1744061313.6950352,8.061453819274902,28284271247.461903
+1744061313.7149067,8.08148455619812,-0.528006175937269,1744061313.7149096,8.08148455619812,-2.5562180491147086,1744061313.7149122,8.08148455619812,0.000530006175937269,1744061313.7149148,8.08148455619812,-56568542383.594315,1744061313.7149165,8.08148455619812,0.065,1744061313.7149181,8.08148455619812,3.1415926535434564,1744061313.7149196,8.08148455619812,2.621207198169708,1744061313.714921,8.08148455619812,3.7745383802917715e-21,1744061313.7149222,8.08148455619812,0.3070713872517473,1744061313.7149246,8.08148455619812,0.0,1744061313.7149258,8.08148455619812,-22627416997.723866,1744061313.7149272,8.08148455619812,0.0,1744061313.7149284,8.08148455619812,28284271247.461903
+1744061313.7352803,8.10145378112793,-0.528006175937269,1744061313.7352834,8.10145378112793,-2.5562180491147086,1744061313.7352862,8.10145378112793,0.000530006175937269,1744061313.735289,8.10145378112793,-56568542383.594315,1744061313.7352903,8.10145378112793,0.065,1744061313.735292,8.10145378112793,3.1415926535434564,1744061313.7352934,8.10145378112793,2.621207198169708,1744061313.7352948,8.10145378112793,3.7745383802917715e-21,1744061313.7352958,8.10145378112793,0.3070713872517473,1744061313.7352974,8.10145378112793,0.0,1744061313.7352986,8.10145378112793,-22627416997.723866,1744061313.7352998,8.10145378112793,0.0,1744061313.7353015,8.10145378112793,28284271247.461903
+1744061313.7548969,8.1214599609375,-0.528006175937269,1744061313.754899,8.1214599609375,-2.5562180491147086,1744061313.7549016,8.1214599609375,0.000530006175937269,1744061313.7549045,8.1214599609375,-56568542383.594315,1744061313.7549062,8.1214599609375,0.065,1744061313.7549076,8.1214599609375,3.1415926535434564,1744061313.7549095,8.1214599609375,2.621207198169708,1744061313.7549107,8.1214599609375,3.7745383802917715e-21,1744061313.754912,8.1214599609375,0.3070713872517473,1744061313.7549138,8.1214599609375,0.0,1744061313.754915,8.1214599609375,-22627416997.723866,1744061313.7549164,8.1214599609375,0.0,1744061313.7549176,8.1214599609375,28284271247.461903
+1744061313.7748349,8.141445636749268,-0.528006175937269,1744061313.7748375,8.141445636749268,-2.5562180491147086,1744061313.7748404,8.141445636749268,0.000530006175937269,1744061313.774843,8.141445636749268,-56568542383.594315,1744061313.7748444,8.141445636749268,0.065,1744061313.7748458,8.141445636749268,3.1415926535434564,1744061313.7748473,8.141445636749268,2.621207198169708,1744061313.7748485,8.141445636749268,3.7745383802917715e-21,1744061313.77485,8.141445636749268,0.3070713872517473,1744061313.7748513,8.141445636749268,0.0,1744061313.7748525,8.141445636749268,-22627416997.723866,1744061313.7748542,8.141445636749268,0.0,1744061313.7748551,8.141445636749268,28284271247.461903
+1744061313.7949598,8.16147232055664,-0.528006175937269,1744061313.7949622,8.16147232055664,-2.5562180491147086,1744061313.7949648,8.16147232055664,0.000530006175937269,1744061313.7949677,8.16147232055664,-56568542383.594315,1744061313.794969,8.16147232055664,0.065,1744061313.7949703,8.16147232055664,3.1415926535434564,1744061313.794972,8.16147232055664,2.621207198169708,1744061313.794973,8.16147232055664,3.7745383802917715e-21,1744061313.7949743,8.16147232055664,0.3070713872517473,1744061313.794976,8.16147232055664,0.0,1744061313.7949772,8.16147232055664,-22627416997.723866,1744061313.7949786,8.16147232055664,0.0,1744061313.7949798,8.16147232055664,28284271247.461903
+1744061313.8148322,8.181454181671143,-0.528006175937269,1744061313.8148344,8.181454181671143,-2.5562180491147086,1744061313.8148375,8.181454181671143,0.000530006175937269,1744061313.81484,8.181454181671143,-56568542383.594315,1744061313.8148417,8.181454181671143,0.065,1744061313.8148437,8.181454181671143,3.1415926535434564,1744061313.814845,8.181454181671143,2.621207198169708,1744061313.8148465,8.181454181671143,3.7745383802917715e-21,1744061313.8148477,8.181454181671143,0.3070713872517473,1744061313.8148496,8.181454181671143,0.0,1744061313.8148508,8.181454181671143,-22627416997.723866,1744061313.814852,8.181454181671143,0.0,1744061313.8148534,8.181454181671143,28284271247.461903
+1744061313.8352149,8.20145297050476,-0.9762868371061098,1744061313.8352182,8.20145297050476,-4.460582133384394,1744061313.8352218,8.20145297050476,0.0009782868371061098,1744061313.8352253,8.20145297050476,-56568542383.594765,1744061313.8352277,8.20145297050476,0.065,1744061313.83523,8.20145297050476,3.1415926535097913,1744061313.8352323,8.20145297050476,4.525591178615246,1744061313.8352337,8.20145297050476,6.516851323081717e-21,1744061313.8352354,8.20145297050476,0.06692503202748035,1744061313.8352458,8.20145297050476,0.0,1744061313.8352473,8.20145297050476,-22627416997.988026,1744061313.8352492,8.20145297050476,0.0,1744061313.8352509,8.20145297050476,28284271247.461903
+1744061313.855288,8.221483707427979,-0.9762868371061098,1744061313.855291,8.221483707427979,-4.460582133384394,1744061313.8552935,8.221483707427979,0.0009782868371061098,1744061313.8552964,8.221483707427979,-56568542383.594765,1744061313.8552976,8.221483707427979,0.065,1744061313.8552992,8.221483707427979,3.1415926535097913,1744061313.8553007,8.221483707427979,4.525591178615246,1744061313.8553019,8.221483707427979,6.516851323081717e-21,1744061313.855303,8.221483707427979,0.06692503202748035,1744061313.8553052,8.221483707427979,0.0,1744061313.8553064,8.221483707427979,-22627416997.915985,1744061313.8553083,8.221483707427979,0.0,1744061313.8553095,8.221483707427979,28284271247.461903
+1744061313.8748453,8.241445541381836,-0.9762868371061098,1744061313.8748474,8.241445541381836,-4.460582133384394,1744061313.87485,8.241445541381836,0.0009782868371061098,1744061313.874853,8.241445541381836,-56568542383.594765,1744061313.874854,8.241445541381836,0.065,1744061313.874856,8.241445541381836,3.1415926535097913,1744061313.8748572,8.241445541381836,4.525591178615246,1744061313.8748584,8.241445541381836,6.516851323081717e-21,1744061313.8748598,8.241445541381836,0.06692503202748035,1744061313.8748615,8.241445541381836,0.0,1744061313.874863,8.241445541381836,-22627416997.915985,1744061313.874864,8.241445541381836,0.0,1744061313.8748653,8.241445541381836,28284271247.461903
+1744061313.8948777,8.261447191238403,-0.9762868371061098,1744061313.8948803,8.261447191238403,-4.460582133384394,1744061313.894883,8.261447191238403,0.0009782868371061098,1744061313.8948853,8.261447191238403,-56568542383.594765,1744061313.894887,8.261447191238403,0.065,1744061313.8948884,8.261447191238403,3.1415926535097913,1744061313.8948905,8.261447191238403,4.525591178615246,1744061313.8948917,8.261447191238403,6.516851323081717e-21,1744061313.8948932,8.261447191238403,0.06692503202748035,1744061313.8948948,8.261447191238403,0.0,1744061313.894896,8.261447191238403,-22627416997.915985,1744061313.8948977,8.261447191238403,0.0,1744061313.894899,8.261447191238403,28284271247.461903
+1744061313.9148629,8.281447172164917,-0.9762868371061098,1744061313.9148655,8.281447172164917,-4.460582133384394,1744061313.9148679,8.281447172164917,0.0009782868371061098,1744061313.9148707,8.281447172164917,-56568542383.594765,1744061313.9148722,8.281447172164917,0.065,1744061313.9148738,8.281447172164917,3.1415926535097913,1744061313.914875,8.281447172164917,4.525591178615246,1744061313.9148765,8.281447172164917,6.516851323081717e-21,1744061313.9148781,8.281447172164917,0.06692503202748035,1744061313.91488,8.281447172164917,0.0,1744061313.9148812,8.281447172164917,-22627416997.915985,1744061313.9148827,8.281447172164917,0.0,1744061313.9148839,8.281447172164917,28284271247.461903
+1744061313.9351819,8.301508903503418,-0.9762868371061098,1744061313.9351842,8.301508903503418,-4.460582133384394,1744061313.9351866,8.301508903503418,0.0009782868371061098,1744061313.9351895,8.301508903503418,-56568542383.594765,1744061313.9351907,8.301508903503418,0.065,1744061313.9351926,8.301508903503418,3.1415926535097913,1744061313.9351938,8.301508903503418,4.525591178615246,1744061313.9351952,8.301508903503418,6.516851323081717e-21,1744061313.9351964,8.301508903503418,0.06692503202748035,1744061313.935198,8.301508903503418,0.0,1744061313.935199,8.301508903503418,-22627416997.915985,1744061313.9352005,8.301508903503418,0.0,1744061313.9352016,8.301508903503418,28284271247.461903
+1744061313.9556355,8.321549415588379,-0.9762868371061098,1744061313.955638,8.321549415588379,-4.460582133384394,1744061313.955641,8.321549415588379,0.0009782868371061098,1744061313.9556437,8.321549415588379,-56568542383.594765,1744061313.9556453,8.321549415588379,0.065,1744061313.9556472,8.321549415588379,3.1415926535097913,1744061313.9556487,8.321549415588379,4.525591178615246,1744061313.9556503,8.321549415588379,6.516851323081717e-21,1744061313.9556515,8.321549415588379,0.06692503202748035,1744061313.9556549,8.321549415588379,0.0,1744061313.9556565,8.321549415588379,-22627416997.915985,1744061313.9556577,8.321549415588379,0.0,1744061313.9556596,8.321549415588379,28284271247.461903
+1744061313.9748437,8.341480016708374,-0.9762868371061098,1744061313.974846,8.341480016708374,-4.460582133384394,1744061313.9748487,8.341480016708374,0.0009782868371061098,1744061313.9748514,8.341480016708374,-56568542383.594765,1744061313.9748528,8.341480016708374,0.065,1744061313.9748547,8.341480016708374,3.1415926535097913,1744061313.974856,8.341480016708374,4.525591178615246,1744061313.9748573,8.341480016708374,6.516851323081717e-21,1744061313.9748585,8.341480016708374,0.06692503202748035,1744061313.97486,8.341480016708374,0.0,1744061313.9748614,8.341480016708374,-22627416997.915985,1744061313.9748628,8.341480016708374,0.0,1744061313.9748638,8.341480016708374,28284271247.461903
+1744061313.9948466,8.36147952079773,-0.9762868371061098,1744061313.9948487,8.36147952079773,-4.460582133384394,1744061313.9948514,8.36147952079773,0.0009782868371061098,1744061313.994854,8.36147952079773,-56568542383.594765,1744061313.9948554,8.36147952079773,0.065,1744061313.9948573,8.36147952079773,3.1415926535097913,1744061313.9948585,8.36147952079773,4.525591178615246,1744061313.9948597,8.36147952079773,6.516851323081717e-21,1744061313.9948611,8.36147952079773,0.06692503202748035,1744061313.9948626,8.36147952079773,0.0,1744061313.994864,8.36147952079773,-22627416997.915985,1744061313.9948654,8.36147952079773,0.0,1744061313.9948666,8.36147952079773,28284271247.461903
+1744061314.0150585,8.381505012512207,-0.9762868371061098,1744061314.0150616,8.381505012512207,-4.460582133384394,1744061314.015064,8.381505012512207,0.0009782868371061098,1744061314.0150666,8.381505012512207,-56568542383.594765,1744061314.015068,8.381505012512207,0.065,1744061314.01507,8.381505012512207,3.1415926535097913,1744061314.0150714,8.381505012512207,4.525591178615246,1744061314.0150728,8.381505012512207,6.516851323081717e-21,1744061314.015074,8.381505012512207,0.06692503202748035,1744061314.015076,8.381505012512207,0.0,1744061314.015077,8.381505012512207,-22627416997.915985,1744061314.0150783,8.381505012512207,0.0,1744061314.0150797,8.381505012512207,28284271247.461903
+1744061314.035216,8.401454448699951,-0.9762868371061098,1744061314.0352197,8.401454448699951,-4.460582133384394,1744061314.0352225,8.401454448699951,0.0009782868371061098,1744061314.0352254,8.401454448699951,-56568542383.594765,1744061314.0352266,8.401454448699951,0.065,1744061314.0352287,8.401454448699951,3.1415926535097913,1744061314.03523,8.401454448699951,4.525591178615246,1744061314.035231,8.401454448699951,6.516851323081717e-21,1744061314.0352325,8.401454448699951,0.06692503202748035,1744061314.035234,8.401454448699951,0.0,1744061314.0352354,8.401454448699951,-22627416997.915985,1744061314.0352366,8.401454448699951,0.0,1744061314.0352378,8.401454448699951,28284271247.461903
+1744061314.0551207,8.42146921157837,-0.9762868371061098,1744061314.0551243,8.42146921157837,-4.460582133384394,1744061314.0551271,8.42146921157837,0.0009782868371061098,1744061314.0551298,8.42146921157837,-56568542383.594765,1744061314.0551314,8.42146921157837,0.065,1744061314.0551329,8.42146921157837,3.1415926535097913,1744061314.0551345,8.42146921157837,4.525591178615246,1744061314.0551357,8.42146921157837,6.516851323081717e-21,1744061314.055137,8.42146921157837,0.06692503202748035,1744061314.0551388,8.42146921157837,0.0,1744061314.0551403,8.42146921157837,-22627416997.915985,1744061314.0551417,8.42146921157837,0.0,1744061314.0551429,8.42146921157837,28284271247.461903
+1744061314.0748441,8.441447496414185,-0.9762868371061098,1744061314.0748465,8.441447496414185,-4.460582133384394,1744061314.0748494,8.441447496414185,0.0009782868371061098,1744061314.0748518,8.441447496414185,-56568542383.594765,1744061314.0748532,8.441447496414185,0.065,1744061314.0748549,8.441447496414185,3.1415926535097913,1744061314.0748563,8.441447496414185,4.525591178615246,1744061314.0748575,8.441447496414185,6.516851323081717e-21,1744061314.0748587,8.441447496414185,0.06692503202748035,1744061314.0748606,8.441447496414185,0.0,1744061314.0748618,8.441447496414185,-22627416997.915985,1744061314.0748632,8.441447496414185,0.0,1744061314.0748644,8.441447496414185,28284271247.461903
+1744061314.0949624,8.461457252502441,-0.9762868371061098,1744061314.0949647,8.461457252502441,-4.460582133384394,1744061314.0949674,8.461457252502441,0.0009782868371061098,1744061314.0949702,8.461457252502441,-56568542383.594765,1744061314.0949717,8.461457252502441,0.065,1744061314.094973,8.461457252502441,3.1415926535097913,1744061314.0949745,8.461457252502441,4.525591178615246,1744061314.0949757,8.461457252502441,6.516851323081717e-21,1744061314.0949767,8.461457252502441,0.06692503202748035,1744061314.0949788,8.461457252502441,0.0,1744061314.0949798,8.461457252502441,-22627416997.915985,1744061314.0949814,8.461457252502441,0.0,1744061314.0949826,8.461457252502441,28284271247.461903
+1744061314.114874,8.481448888778687,-0.9762868371061098,1744061314.1148765,8.481448888778687,-4.460582133384394,1744061314.114879,8.481448888778687,0.0009782868371061098,1744061314.1148818,8.481448888778687,-56568542383.594765,1744061314.1148834,8.481448888778687,0.065,1744061314.1148849,8.481448888778687,3.1415926535097913,1744061314.114886,8.481448888778687,4.525591178615246,1744061314.1148875,8.481448888778687,6.516851323081717e-21,1744061314.1148887,8.481448888778687,0.06692503202748035,1744061314.1148906,8.481448888778687,0.0,1744061314.1148918,8.481448888778687,-22627416997.915985,1744061314.114893,8.481448888778687,0.0,1744061314.1148944,8.481448888778687,28284271247.461903
+1744061314.135237,8.501446008682251,-0.9762868371061098,1744061314.135239,8.501446008682251,-4.460582133384394,1744061314.1352417,8.501446008682251,0.0009782868371061098,1744061314.1352444,8.501446008682251,-56568542383.594765,1744061314.1352456,8.501446008682251,0.065,1744061314.1352475,8.501446008682251,3.1415926535097913,1744061314.1352487,8.501446008682251,4.525591178615246,1744061314.1352499,8.501446008682251,6.516851323081717e-21,1744061314.135251,8.501446008682251,0.06692503202748035,1744061314.1352525,8.501446008682251,0.0,1744061314.1352537,8.501446008682251,-22627416997.915985,1744061314.135255,8.501446008682251,0.0,1744061314.1352563,8.501446008682251,28284271247.461903
+1744061314.1554604,8.521493673324585,-0.9762868371061098,1744061314.155463,8.521493673324585,-4.460582133384394,1744061314.155466,8.521493673324585,0.0009782868371061098,1744061314.1554687,8.521493673324585,-56568542383.594765,1744061314.1554704,8.521493673324585,0.065,1744061314.155472,8.521493673324585,3.1415926535097913,1744061314.1554737,8.521493673324585,4.525591178615246,1744061314.155475,8.521493673324585,6.516851323081717e-21,1744061314.1554763,8.521493673324585,0.06692503202748035,1744061314.1554782,8.521493673324585,0.0,1744061314.15548,8.521493673324585,-22627416997.915985,1744061314.1554818,8.521493673324585,0.0,1744061314.1554832,8.521493673324585,28284271247.461903
+1744061314.1748672,8.541446208953857,-0.9762868371061098,1744061314.1748698,8.541446208953857,-4.460582133384394,1744061314.1748734,8.541446208953857,0.0009782868371061098,1744061314.1748774,8.541446208953857,-56568542383.594765,1744061314.1748798,8.541446208953857,0.065,1744061314.1748827,8.541446208953857,3.1415926535097913,1744061314.1748846,8.541446208953857,4.525591178615246,1744061314.1748865,8.541446208953857,6.516851323081717e-21,1744061314.1748886,8.541446208953857,0.06692503202748035,1744061314.174892,8.541446208953857,0.0,1744061314.1748943,8.541446208953857,-22627416997.915985,1744061314.1748967,8.541446208953857,0.0,1744061314.1748986,8.541446208953857,28284271247.461903
+1744061314.1947684,8.561471223831177,-0.9762868371061098,1744061314.19477,8.561471223831177,-4.460582133384394,1744061314.1947725,8.561471223831177,0.0009782868371061098,1744061314.1947744,8.561471223831177,-56568542383.594765,1744061314.1947753,8.561471223831177,0.065,1744061314.1947765,8.561471223831177,3.1415926535097913,1744061314.1947775,8.561471223831177,4.525591178615246,1744061314.1947784,8.561471223831177,6.516851323081717e-21,1744061314.1947794,8.561471223831177,0.06692503202748035,1744061314.1947806,8.561471223831177,0.0,1744061314.1947818,8.561471223831177,-22627416997.915985,1744061314.1947827,8.561471223831177,0.0,1744061314.1947834,8.561471223831177,28284271247.461903
+1744061314.2146726,8.581446409225464,-0.9762868371061098,1744061314.2146745,8.581446409225464,-4.460582133384394,1744061314.2146764,8.581446409225464,0.0009782868371061098,1744061314.2146785,8.581446409225464,-56568542383.594765,1744061314.2146795,8.581446409225464,0.065,1744061314.2146811,8.581446409225464,3.1415926535097913,1744061314.214682,8.581446409225464,4.525591178615246,1744061314.2146828,8.581446409225464,6.516851323081717e-21,1744061314.2146842,8.581446409225464,0.06692503202748035,1744061314.214686,8.581446409225464,0.0,1744061314.2146878,8.581446409225464,-22627416997.915985,1744061314.2146957,8.581446409225464,0.0,1744061314.2146966,8.581446409225464,28284271247.461903
+1744061314.2351482,8.601496934890747,-0.9762868371061098,1744061314.2351499,8.601496934890747,-4.460582133384394,1744061314.2351518,8.601496934890747,0.0009782868371061098,1744061314.235154,8.601496934890747,-56568542383.594765,1744061314.2351549,8.601496934890747,0.065,1744061314.235156,8.601496934890747,3.1415926535097913,1744061314.2351573,8.601496934890747,4.525591178615246,1744061314.235158,8.601496934890747,6.516851323081717e-21,1744061314.2351592,8.601496934890747,0.06692503202748035,1744061314.23516,8.601496934890747,0.0,1744061314.235161,8.601496934890747,-22627416997.915985,1744061314.235162,8.601496934890747,0.0,1744061314.235163,8.601496934890747,28284271247.461903
+1744061314.2551951,8.621495723724365,-0.9762868371061098,1744061314.2551985,8.621495723724365,-4.460582133384394,1744061314.2552016,8.621495723724365,0.0009782868371061098,1744061314.2552044,8.621495723724365,-56568542383.594765,1744061314.2552056,8.621495723724365,0.065,1744061314.2552078,8.621495723724365,3.1415926535097913,1744061314.2552092,8.621495723724365,4.525591178615246,1744061314.25521,8.621495723724365,6.516851323081717e-21,1744061314.2552114,8.621495723724365,0.06692503202748035,1744061314.2552135,8.621495723724365,0.0,1744061314.2552328,8.621495723724365,-22627416997.915985,1744061314.2552342,8.621495723724365,0.0,1744061314.2552357,8.621495723724365,28284271247.461903
+1744061314.2747374,8.64144515991211,-0.9762868371061098,1744061314.2747397,8.64144515991211,-4.460582133384394,1744061314.2747416,8.64144515991211,0.0009782868371061098,1744061314.2747438,8.64144515991211,-56568542383.594765,1744061314.2747447,8.64144515991211,0.065,1744061314.2747462,8.64144515991211,3.1415926535097913,1744061314.2747471,8.64144515991211,4.525591178615246,1744061314.2747478,8.64144515991211,6.516851323081717e-21,1744061314.274749,8.64144515991211,0.06692503202748035,1744061314.2747505,8.64144515991211,0.0,1744061314.2747512,8.64144515991211,-22627416997.915985,1744061314.2747526,8.64144515991211,0.0,1744061314.2747536,8.64144515991211,28284271247.461903
+1744061314.2946749,8.661473989486694,-0.9762868371061098,1744061314.2946768,8.661473989486694,-4.460582133384394,1744061314.2946787,8.661473989486694,0.0009782868371061098,1744061314.2946808,8.661473989486694,-56568542383.594765,1744061314.2946818,8.661473989486694,0.065,1744061314.2946832,8.661473989486694,3.1415926535097913,1744061314.2946842,8.661473989486694,4.525591178615246,1744061314.294685,8.661473989486694,6.516851323081717e-21,1744061314.2946858,8.661473989486694,0.06692503202748035,1744061314.2946873,8.661473989486694,0.0,1744061314.294688,8.661473989486694,-22627416997.915985,1744061314.2946892,8.661473989486694,0.0,1744061314.2946901,8.661473989486694,28284271247.461903
+1744061314.3147154,8.681480407714844,-0.9762868371061098,1744061314.3147173,8.681480407714844,-4.460582133384394,1744061314.3147192,8.681480407714844,0.0009782868371061098,1744061314.3147213,8.681480407714844,-56568542383.594765,1744061314.3147223,8.681480407714844,0.065,1744061314.3147235,8.681480407714844,3.1415926535097913,1744061314.3147247,8.681480407714844,4.525591178615246,1744061314.3147254,8.681480407714844,6.516851323081717e-21,1744061314.3147264,8.681480407714844,0.06692503202748035,1744061314.3147283,8.681480407714844,0.0,1744061314.314729,8.681480407714844,-22627416997.915985,1744061314.3147302,8.681480407714844,0.0,1744061314.3147311,8.681480407714844,28284271247.461903
+1744061314.3352377,8.701443910598755,-1.5670871539413427,1744061314.3352394,8.701443910598755,-6.895410609390665,1744061314.3352416,8.701443910598755,0.021416487838947597,1744061314.3352435,8.701443910598755,-56568542383.615204,1744061314.3352447,8.701443910598755,0.065,1744061314.3352456,8.701443910598755,3.1415926534667493,1744061314.3352466,8.701443910598755,6.960415194199999,1744061314.3352475,8.701443910598755,1.0022997919647359e-20,1744061314.3352485,8.701443910598755,0.009542102561806664,1744061314.3352497,8.701443910598755,0.0,1744061314.3352504,8.701443910598755,-22627416997.97911,1744061314.3352516,8.701443910598755,0.0,1744061314.3352523,8.701443910598755,28284271247.461903
+1744061314.355252,8.721804141998291,-1.5670871539413427,1744061314.355254,8.721804141998291,-6.895410609390665,1744061314.3552566,8.721804141998291,0.021416487838947597,1744061314.355259,8.721804141998291,-56568542383.615204,1744061314.3552601,8.721804141998291,0.065,1744061314.3552613,8.721804141998291,3.1415926534667493,1744061314.3552625,8.721804141998291,6.960415194199999,1744061314.3552635,8.721804141998291,1.0022997919647359e-20,1744061314.3552647,8.721804141998291,0.009542102561806664,1744061314.355266,8.721804141998291,0.0,1744061314.3552668,8.721804141998291,-22627416997.96189,1744061314.3552682,8.721804141998291,0.0,1744061314.3552694,8.721804141998291,28284271247.461903
+1744061314.3748074,8.741450309753418,-1.5670871539413427,1744061314.3748093,8.741450309753418,-6.895410609390665,1744061314.3748116,8.741450309753418,0.021416487838947597,1744061314.374814,8.741450309753418,-56568542383.615204,1744061314.374815,8.741450309753418,0.065,1744061314.3748164,8.741450309753418,3.1415926534667493,1744061314.3748178,8.741450309753418,6.960415194199999,1744061314.3748186,8.741450309753418,1.0022997919647359e-20,1744061314.3748195,8.741450309753418,0.009542102561806664,1744061314.3748207,8.741450309753418,0.0,1744061314.3748217,8.741450309753418,-22627416997.96189,1744061314.3748226,8.741450309753418,0.0,1744061314.3748236,8.741450309753418,28284271247.461903
+1744061314.3947518,8.761477708816528,-1.5670871539413427,1744061314.3947544,8.761477708816528,-6.895410609390665,1744061314.3947582,8.761477708816528,0.021416487838947597,1744061314.3947613,8.761477708816528,-56568542383.615204,1744061314.394763,8.761477708816528,0.065,1744061314.3947651,8.761477708816528,3.1415926534667493,1744061314.3947668,8.761477708816528,6.960415194199999,1744061314.3947675,8.761477708816528,1.0022997919647359e-20,1744061314.3947687,8.761477708816528,0.009542102561806664,1744061314.39477,8.761477708816528,0.0,1744061314.3947706,8.761477708816528,-22627416997.96189,1744061314.3947718,8.761477708816528,0.0,1744061314.3947728,8.761477708816528,28284271247.461903
+1744061314.4146807,8.781450271606445,-1.5670871539413427,1744061314.4146826,8.781450271606445,-6.895410609390665,1744061314.414685,8.781450271606445,0.021416487838947597,1744061314.414687,8.781450271606445,-56568542383.615204,1744061314.4146883,8.781450271606445,0.065,1744061314.4146895,8.781450271606445,3.1415926534667493,1744061314.4146905,8.781450271606445,6.960415194199999,1744061314.4146917,8.781450271606445,1.0022997919647359e-20,1744061314.4146924,8.781450271606445,0.009542102561806664,1744061314.4146936,8.781450271606445,0.0,1744061314.4146943,8.781450271606445,-22627416997.96189,1744061314.4146955,8.781450271606445,0.0,1744061314.4146962,8.781450271606445,28284271247.461903
+1744061314.4351156,8.801493167877197,-1.5670871539413427,1744061314.435117,8.801493167877197,-6.895410609390665,1744061314.4351194,8.801493167877197,0.021416487838947597,1744061314.4351213,8.801493167877197,-56568542383.615204,1744061314.4351225,8.801493167877197,0.065,1744061314.4351234,8.801493167877197,3.1415926534667493,1744061314.4351246,8.801493167877197,6.960415194199999,1744061314.4351256,8.801493167877197,1.0022997919647359e-20,1744061314.4351265,8.801493167877197,0.009542102561806664,1744061314.4351275,8.801493167877197,0.0,1744061314.4351282,8.801493167877197,-22627416997.96189,1744061314.4351294,8.801493167877197,0.0,1744061314.4351304,8.801493167877197,28284271247.461903
+1744061314.4553814,8.821517944335938,-1.5670871539413427,1744061314.4553835,8.821517944335938,-6.895410609390665,1744061314.455386,8.821517944335938,0.021416487838947597,1744061314.455388,8.821517944335938,-56568542383.615204,1744061314.4553895,8.821517944335938,0.065,1744061314.4553907,8.821517944335938,3.1415926534667493,1744061314.455392,8.821517944335938,6.960415194199999,1744061314.4553928,8.821517944335938,1.0022997919647359e-20,1744061314.4553938,8.821517944335938,0.009542102561806664,1744061314.4553947,8.821517944335938,0.0,1744061314.455396,8.821517944335938,-22627416997.96189,1744061314.455397,8.821517944335938,0.0,1744061314.4553976,8.821517944335938,28284271247.461903
+1744061314.474656,8.841442346572876,-1.5670871539413427,1744061314.474658,8.841442346572876,-6.895410609390665,1744061314.4746604,8.841442346572876,0.021416487838947597,1744061314.4746623,8.841442346572876,-56568542383.615204,1744061314.4746635,8.841442346572876,0.065,1744061314.4746647,8.841442346572876,3.1415926534667493,1744061314.4746656,8.841442346572876,6.960415194199999,1744061314.4746668,8.841442346572876,1.0022997919647359e-20,1744061314.4746675,8.841442346572876,0.009542102561806664,1744061314.4746687,8.841442346572876,0.0,1744061314.4746695,8.841442346572876,-22627416997.96189,1744061314.4746706,8.841442346572876,0.0,1744061314.4746714,8.841442346572876,28284271247.461903
+1744061314.4949467,8.861515283584595,-1.5670871539413427,1744061314.4949493,8.861515283584595,-6.895410609390665,1744061314.4949522,8.861515283584595,0.021416487838947597,1744061314.4949546,8.861515283584595,-56568542383.615204,1744061314.494956,8.861515283584595,0.065,1744061314.494958,8.861515283584595,3.1415926534667493,1744061314.49496,8.861515283584595,6.960415194199999,1744061314.4949608,8.861515283584595,1.0022997919647359e-20,1744061314.4949627,8.861515283584595,0.009542102561806664,1744061314.4949641,8.861515283584595,0.0,1744061314.4949653,8.861515283584595,-22627416997.96189,1744061314.4949667,8.861515283584595,0.0,1744061314.4949677,8.861515283584595,28284271247.461903
+1744061314.5146704,8.88147783279419,-1.5670871539413427,1744061314.514672,8.88147783279419,-6.895410609390665,1744061314.5146747,8.88147783279419,0.021416487838947597,1744061314.5146768,8.88147783279419,-56568542383.615204,1744061314.5146778,8.88147783279419,0.065,1744061314.514679,8.88147783279419,3.1415926534667493,1744061314.5146801,8.88147783279419,6.960415194199999,1744061314.5146813,8.88147783279419,1.0022997919647359e-20,1744061314.5146823,8.88147783279419,0.009542102561806664,1744061314.5146837,8.88147783279419,0.0,1744061314.5146847,8.88147783279419,-22627416997.96189,1744061314.5146856,8.88147783279419,0.0,1744061314.5146863,8.88147783279419,28284271247.461903
+1744061314.5351057,8.901494979858398,-1.5670871539413427,1744061314.5351076,8.901494979858398,-6.895410609390665,1744061314.5351095,8.901494979858398,0.021416487838947597,1744061314.5351117,8.901494979858398,-56568542383.615204,1744061314.5351126,8.901494979858398,0.065,1744061314.535114,8.901494979858398,3.1415926534667493,1744061314.535115,8.901494979858398,6.960415194199999,1744061314.5351157,8.901494979858398,1.0022997919647359e-20,1744061314.535117,8.901494979858398,0.009542102561806664,1744061314.535118,8.901494979858398,0.0,1744061314.5351188,8.901494979858398,-22627416997.96189,1744061314.5351198,8.901494979858398,0.0,1744061314.535121,8.901494979858398,28284271247.461903
+1744061314.554769,8.921448707580566,-1.5670871539413427,1744061314.554771,8.921448707580566,-6.895410609390665,1744061314.554774,8.921448707580566,0.021416487838947597,1744061314.554776,8.921448707580566,-56568542383.615204,1744061314.5547776,8.921448707580566,0.065,1744061314.5547788,8.921448707580566,3.1415926534667493,1744061314.55478,8.921448707580566,6.960415194199999,1744061314.5547807,8.921448707580566,1.0022997919647359e-20,1744061314.5547817,8.921448707580566,0.009542102561806664,1744061314.5547829,8.921448707580566,0.0,1744061314.5547843,8.921448707580566,-22627416997.96189,1744061314.5547853,8.921448707580566,0.0,1744061314.554786,8.921448707580566,28284271247.461903
+1744061314.5750482,8.941446781158447,-1.5670871539413427,1744061314.5750504,8.941446781158447,-6.895410609390665,1744061314.5750527,8.941446781158447,0.021416487838947597,1744061314.5750551,8.941446781158447,-56568542383.615204,1744061314.575056,8.941446781158447,0.065,1744061314.5750766,8.941446781158447,3.1415926534667493,1744061314.5750778,8.941446781158447,6.960415194199999,1744061314.575079,8.941446781158447,1.0022997919647359e-20,1744061314.57508,8.941446781158447,0.009542102561806664,1744061314.575081,8.941446781158447,0.0,1744061314.5750823,8.941446781158447,-22627416997.96189,1744061314.5750833,8.941446781158447,0.0,1744061314.5750842,8.941446781158447,28284271247.461903
+1744061314.5948353,8.961455821990967,-1.5670871539413427,1744061314.594837,8.961455821990967,-6.895410609390665,1744061314.5948393,8.961455821990967,0.021416487838947597,1744061314.5948417,8.961455821990967,-56568542383.615204,1744061314.5948427,8.961455821990967,0.065,1744061314.5948436,8.961455821990967,3.1415926534667493,1744061314.5948448,8.961455821990967,6.960415194199999,1744061314.5948458,8.961455821990967,1.0022997919647359e-20,1744061314.5948467,8.961455821990967,0.009542102561806664,1744061314.5948477,8.961455821990967,0.0,1744061314.5948489,8.961455821990967,-22627416997.96189,1744061314.5948496,8.961455821990967,0.0,1744061314.5948505,8.961455821990967,28284271247.461903
+1744061314.6147099,8.981471538543701,-1.5670871539413427,1744061314.6147115,8.981471538543701,-6.895410609390665,1744061314.614714,8.981471538543701,0.021416487838947597,1744061314.6147158,8.981471538543701,-56568542383.615204,1744061314.614717,8.981471538543701,0.065,1744061314.6147182,8.981471538543701,3.1415926534667493,1744061314.6147192,8.981471538543701,6.960415194199999,1744061314.6147203,8.981471538543701,1.0022997919647359e-20,1744061314.614721,8.981471538543701,0.009542102561806664,1744061314.6147225,8.981471538543701,0.0,1744061314.6147234,8.981471538543701,-22627416997.96189,1744061314.6147244,8.981471538543701,0.0,1744061314.6147254,8.981471538543701,28284271247.461903
+1744061314.6348882,9.001444339752197,-1.5670871539413427,1744061314.63489,9.001444339752197,-6.895410609390665,1744061314.634892,9.001444339752197,0.021416487838947597,1744061314.6348941,9.001444339752197,-56568542383.615204,1744061314.634895,9.001444339752197,0.065,1744061314.6348963,9.001444339752197,3.1415926534667493,1744061314.6348975,9.001444339752197,6.960415194199999,1744061314.6348984,9.001444339752197,1.0022997919647359e-20,1744061314.6348994,9.001444339752197,0.009542102561806664,1744061314.6349006,9.001444339752197,0.0,1744061314.6349013,9.001444339752197,-22627416997.96189,1744061314.6349022,9.001444339752197,0.0,1744061314.6349032,9.001444339752197,28284271247.461903
+1744061314.6548574,9.021478414535522,-1.5670871539413427,1744061314.6548746,9.021478414535522,-6.895410609390665,1744061314.654877,9.021478414535522,0.021416487838947597,1744061314.654879,9.021478414535522,-56568542383.615204,1744061314.65488,9.021478414535522,0.065,1744061314.6548815,9.021478414535522,3.1415926534667493,1744061314.6548827,9.021478414535522,6.960415194199999,1744061314.6548834,9.021478414535522,1.0022997919647359e-20,1744061314.654884,9.021478414535522,0.009542102561806664,1744061314.6548853,9.021478414535522,0.0,1744061314.6548862,9.021478414535522,-22627416997.96189,1744061314.6548872,9.021478414535522,0.0,1744061314.6548882,9.021478414535522,28284271247.461903
+1744061314.67471,9.041480302810669,-1.5670871539413427,1744061314.6747117,9.041480302810669,-6.895410609390665,1744061314.674714,9.041480302810669,0.021416487838947597,1744061314.6747162,9.041480302810669,-56568542383.615204,1744061314.6747172,9.041480302810669,0.065,1744061314.6747184,9.041480302810669,3.1415926534667493,1744061314.6747196,9.041480302810669,6.960415194199999,1744061314.6747203,9.041480302810669,1.0022997919647359e-20,1744061314.6747212,9.041480302810669,0.009542102561806664,1744061314.6747222,9.041480302810669,0.0,1744061314.6747234,9.041480302810669,-22627416997.96189,1744061314.674724,9.041480302810669,0.0,1744061314.674725,9.041480302810669,28284271247.461903
+1744061314.6957326,9.061646223068237,-1.5670871539413427,1744061314.6957362,9.061646223068237,-6.895410609390665,1744061314.6957405,9.061646223068237,0.021416487838947597,1744061314.695744,9.061646223068237,-56568542383.615204,1744061314.695746,9.061646223068237,0.065,1744061314.695748,9.061646223068237,3.1415926534667493,1744061314.6957502,9.061646223068237,6.960415194199999,1744061314.6957517,9.061646223068237,1.0022997919647359e-20,1744061314.6957536,9.061646223068237,0.009542102561806664,1744061314.6957552,9.061646223068237,0.0,1744061314.6957572,9.061646223068237,-22627416997.96189,1744061314.6957588,9.061646223068237,0.0,1744061314.695761,9.061646223068237,28284271247.461903
+1744061314.71477,9.081485033035278,-1.5670871539413427,1744061314.7147722,9.081485033035278,-6.895410609390665,1744061314.7147746,9.081485033035278,0.021416487838947597,1744061314.7147765,9.081485033035278,-56568542383.615204,1744061314.714778,9.081485033035278,0.065,1744061314.714779,9.081485033035278,3.1415926534667493,1744061314.71478,9.081485033035278,6.960415194199999,1744061314.714781,9.081485033035278,1.0022997919647359e-20,1744061314.714782,9.081485033035278,0.009542102561806664,1744061314.714783,9.081485033035278,0.0,1744061314.714784,9.081485033035278,-22627416997.96189,1744061314.7147849,9.081485033035278,0.0,1744061314.7147858,9.081485033035278,28284271247.461903
+1744061314.7349603,9.101465225219727,-1.5670871539413427,1744061314.734963,9.101465225219727,-6.895410609390665,1744061314.7349653,9.101465225219727,0.021416487838947597,1744061314.7349672,9.101465225219727,-56568542383.615204,1744061314.7349684,9.101465225219727,0.065,1744061314.7349696,9.101465225219727,3.1415926534667493,1744061314.7349706,9.101465225219727,6.960415194199999,1744061314.7349718,9.101465225219727,1.0022997919647359e-20,1744061314.734973,9.101465225219727,0.009542102561806664,1744061314.7349741,9.101465225219727,0.0,1744061314.7349756,9.101465225219727,-22627416997.96189,1744061314.7349768,9.101465225219727,0.0,1744061314.7349775,9.101465225219727,28284271247.461903
+1744061314.7559104,9.121543169021606,-1.5670871539413427,1744061314.7559128,9.121543169021606,-6.895410609390665,1744061314.7559152,9.121543169021606,0.021416487838947597,1744061314.7559173,9.121543169021606,-56568542383.615204,1744061314.7559187,9.121543169021606,0.065,1744061314.7559202,9.121543169021606,3.1415926534667493,1744061314.7559214,9.121543169021606,6.960415194199999,1744061314.755922,9.121543169021606,1.0022997919647359e-20,1744061314.7559233,9.121543169021606,0.009542102561806664,1744061314.7559242,9.121543169021606,0.0,1744061314.7559252,9.121543169021606,-22627416997.96189,1744061314.7559264,9.121543169021606,0.0,1744061314.7559273,9.121543169021606,28284271247.461903
+1744061314.7746353,9.141445875167847,-1.5670871539413427,1744061314.774637,9.141445875167847,-6.895410609390665,1744061314.7746394,9.141445875167847,0.021416487838947597,1744061314.7746415,9.141445875167847,-56568542383.615204,1744061314.7746425,9.141445875167847,0.065,1744061314.7746437,9.141445875167847,3.1415926534667493,1744061314.7746449,9.141445875167847,6.960415194199999,1744061314.7746458,9.141445875167847,1.0022997919647359e-20,1744061314.7746465,9.141445875167847,0.009542102561806664,1744061314.7746475,9.141445875167847,0.0,1744061314.7746487,9.141445875167847,-22627416997.96189,1744061314.7746496,9.141445875167847,0.0,1744061314.7746503,9.141445875167847,28284271247.461903
+1744061314.7949095,9.161500215530396,-1.5670871539413427,1744061314.7949111,9.161500215530396,-6.895410609390665,1744061314.7949135,9.161500215530396,0.021416487838947597,1744061314.7949157,9.161500215530396,-56568542383.615204,1744061314.7949166,9.161500215530396,0.065,1744061314.794918,9.161500215530396,3.1415926534667493,1744061314.7949193,9.161500215530396,6.960415194199999,1744061314.7949202,9.161500215530396,1.0022997919647359e-20,1744061314.794921,9.161500215530396,0.009542102561806664,1744061314.7949224,9.161500215530396,0.0,1744061314.7949233,9.161500215530396,-22627416997.96189,1744061314.7949243,9.161500215530396,0.0,1744061314.7949252,9.161500215530396,28284271247.461903
+1744061314.8147223,9.181473970413208,-1.5670871539413427,1744061314.8147242,9.181473970413208,-6.895410609390665,1744061314.8147264,9.181473970413208,0.021416487838947597,1744061314.8147285,9.181473970413208,-56568542383.615204,1744061314.8147297,9.181473970413208,0.065,1744061314.8147311,9.181473970413208,3.1415926534667493,1744061314.8147323,9.181473970413208,6.960415194199999,1744061314.8147333,9.181473970413208,1.0022997919647359e-20,1744061314.814734,9.181473970413208,0.009542102561806664,1744061314.8147357,9.181473970413208,0.0,1744061314.8147366,9.181473970413208,-22627416997.96189,1744061314.8147373,9.181473970413208,0.0,1744061314.8147385,9.181473970413208,28284271247.461903
+1744061314.8348854,9.201483726501465,-2.1765207440211434,1744061314.834887,9.201483726501465,-9.775638520753052,1744061314.834889,9.201483726501465,0.021416487838947597,1744061314.834891,9.201483726501465,-56568542383.615204,1744061314.8348923,9.201483726501465,0.065,1744061314.8348935,9.201483726501465,3.1415926534158336,1744061314.8348947,9.201483726501465,9.840643037515031,1744061314.8348954,9.201483726501465,1.4170526030878115e-20,1744061314.8348963,9.201483726501465,0.0009526874255039789,1744061314.8348975,9.201483726501465,0.0,1744061314.8348982,9.201483726501465,-22627416997.971336,1744061314.8348994,9.201483726501465,0.0,1744061314.8349001,9.201483726501465,28284271247.461903
+1744061314.8550222,9.221485614776611,-2.1765207440211434,1744061314.8550246,9.221485614776611,-9.775638520753052,1744061314.8550272,9.221485614776611,0.021416487838947597,1744061314.8550296,9.221485614776611,-56568542383.615204,1744061314.8550308,9.221485614776611,0.065,1744061314.855032,9.221485614776611,3.1415926534158336,1744061314.8550334,9.221485614776611,9.840643037515031,1744061314.855034,9.221485614776611,1.4170526030878115e-20,1744061314.855035,9.221485614776611,0.0009526874255039789,1744061314.8550367,9.221485614776611,0.0,1744061314.8550377,9.221485614776611,-22627416997.96876,1744061314.8550386,9.221485614776611,0.0,1744061314.8550398,9.221485614776611,28284271247.461903
+1744061314.8746574,9.241478443145752,-2.1765207440211434,1744061314.874659,9.241478443145752,-9.775638520753052,1744061314.874662,9.241478443145752,0.021416487838947597,1744061314.8746636,9.241478443145752,-56568542383.615204,1744061314.874665,9.241478443145752,0.065,1744061314.874666,9.241478443145752,3.1415926534158336,1744061314.874667,9.241478443145752,9.840643037515031,1744061314.8746681,9.241478443145752,1.4170526030878115e-20,1744061314.8746688,9.241478443145752,0.0009526874255039789,1744061314.87467,9.241478443145752,0.0,1744061314.8746707,9.241478443145752,-22627416997.96876,1744061314.8746722,9.241478443145752,0.0,1744061314.874673,9.241478443145752,28284271247.461903
+1744061314.8949027,9.261500120162964,-2.1765207440211434,1744061314.8949046,9.261500120162964,-9.775638520753052,1744061314.894907,9.261500120162964,0.021416487838947597,1744061314.8949091,9.261500120162964,-56568542383.615204,1744061314.89491,9.261500120162964,0.065,1744061314.8949113,9.261500120162964,3.1415926534158336,1744061314.8949122,9.261500120162964,9.840643037515031,1744061314.8949132,9.261500120162964,1.4170526030878115e-20,1744061314.8949142,9.261500120162964,0.0009526874255039789,1744061314.8949153,9.261500120162964,0.0,1744061314.8949163,9.261500120162964,-22627416997.96876,1744061314.8949175,9.261500120162964,0.0,1744061314.8949184,9.261500120162964,28284271247.461903
+1744061314.9147582,9.281489849090576,-2.1765207440211434,1744061314.9147599,9.281489849090576,-9.775638520753052,1744061314.9147623,9.281489849090576,0.021416487838947597,1744061314.9147644,9.281489849090576,-56568542383.615204,1744061314.9147654,9.281489849090576,0.065,1744061314.9147668,9.281489849090576,3.1415926534158336,1744061314.914768,9.281489849090576,9.840643037515031,1744061314.914769,9.281489849090576,1.4170526030878115e-20,1744061314.9147696,9.281489849090576,0.0009526874255039789,1744061314.9147708,9.281489849090576,0.0,1744061314.914772,9.281489849090576,-22627416997.96876,1744061314.914773,9.281489849090576,0.0,1744061314.9147737,9.281489849090576,28284271247.461903
+1744061314.934944,9.30147647857666,-2.1765207440211434,1744061314.9349458,9.30147647857666,-9.775638520753052,1744061314.9349482,9.30147647857666,0.021416487838947597,1744061314.9349504,9.30147647857666,-56568542383.615204,1744061314.9349513,9.30147647857666,0.065,1744061314.9349527,9.30147647857666,3.1415926534158336,1744061314.9349537,9.30147647857666,9.840643037515031,1744061314.9349544,9.30147647857666,1.4170526030878115e-20,1744061314.9349554,9.30147647857666,0.0009526874255039789,1744061314.9349566,9.30147647857666,0.0,1744061314.9349573,9.30147647857666,-22627416997.96876,1744061314.9349582,9.30147647857666,0.0,1744061314.9349592,9.30147647857666,28284271247.461903
+1744061314.9553173,9.321577548980713,-2.1765207440211434,1744061314.95532,9.321577548980713,-9.775638520753052,1744061314.9553227,9.321577548980713,0.021416487838947597,1744061314.955325,9.321577548980713,-56568542383.615204,1744061314.9553258,9.321577548980713,0.065,1744061314.9553273,9.321577548980713,3.1415926534158336,1744061314.9553285,9.321577548980713,9.840643037515031,1744061314.9553294,9.321577548980713,1.4170526030878115e-20,1744061314.9553306,9.321577548980713,0.0009526874255039789,1744061314.955332,9.321577548980713,0.0,1744061314.9553335,9.321577548980713,-22627416997.96876,1744061314.9553344,9.321577548980713,0.0,1744061314.9553356,9.321577548980713,28284271247.461903
+1744061314.9748514,9.341447353363037,-2.1765207440211434,1744061314.974855,9.341447353363037,-9.775638520753052,1744061314.9748578,9.341447353363037,0.021416487838947597,1744061314.9748602,9.341447353363037,-56568542383.615204,1744061314.9748623,9.341447353363037,0.065,1744061314.9748642,9.341447353363037,3.1415926534158336,1744061314.974866,9.341447353363037,9.840643037515031,1744061314.9748673,9.341447353363037,1.4170526030878115e-20,1744061314.974869,9.341447353363037,0.0009526874255039789,1744061314.9748704,9.341447353363037,0.0,1744061314.9748788,9.341447353363037,-22627416997.96876,1744061314.97488,9.341447353363037,0.0,1744061314.9748812,9.341447353363037,28284271247.461903
+1744061314.9951499,9.361495733261108,-2.1765207440211434,1744061314.9951525,9.361495733261108,-9.775638520753052,1744061314.9951615,9.361495733261108,0.021416487838947597,1744061314.9951644,9.361495733261108,-56568542383.615204,1744061314.9951653,9.361495733261108,0.065,1744061314.995167,9.361495733261108,3.1415926534158336,1744061314.9951677,9.361495733261108,9.840643037515031,1744061314.995188,9.361495733261108,1.4170526030878115e-20,1744061314.9951887,9.361495733261108,0.0009526874255039789,1744061314.99519,9.361495733261108,0.0,1744061314.995191,9.361495733261108,-22627416997.96876,1744061314.995192,9.361495733261108,0.0,1744061314.995193,9.361495733261108,28284271247.461903
+1744061315.0147035,9.381452083587646,-2.1765207440211434,1744061315.0147054,9.381452083587646,-9.775638520753052,1744061315.0147078,9.381452083587646,0.021416487838947597,1744061315.0147097,9.381452083587646,-56568542383.615204,1744061315.014711,9.381452083587646,0.065,1744061315.014712,9.381452083587646,3.1415926534158336,1744061315.014713,9.381452083587646,9.840643037515031,1744061315.014714,9.381452083587646,1.4170526030878115e-20,1744061315.014715,9.381452083587646,0.0009526874255039789,1744061315.0147161,9.381452083587646,0.0,1744061315.014717,9.381452083587646,-22627416997.96876,1744061315.0147183,9.381452083587646,0.0,1744061315.0147192,9.381452083587646,28284271247.461903
+1744061315.0348723,9.401440382003784,-2.1765207440211434,1744061315.0348742,9.401440382003784,-9.775638520753052,1744061315.034876,9.401440382003784,0.021416487838947597,1744061315.0348785,9.401440382003784,-56568542383.615204,1744061315.0348794,9.401440382003784,0.065,1744061315.0348809,9.401440382003784,3.1415926534158336,1744061315.0348818,9.401440382003784,9.840643037515031,1744061315.0348825,9.401440382003784,1.4170526030878115e-20,1744061315.0348835,9.401440382003784,0.0009526874255039789,1744061315.034885,9.401440382003784,0.0,1744061315.0348864,9.401440382003784,-22627416997.96876,1744061315.034888,9.401440382003784,0.0,1744061315.0348895,9.401440382003784,28284271247.461903
+1744061315.0557108,9.421514511108398,-2.1765207440211434,1744061315.0557137,9.421514511108398,-9.775638520753052,1744061315.0557172,9.421514511108398,0.021416487838947597,1744061315.0557194,9.421514511108398,-56568542383.615204,1744061315.0557215,9.421514511108398,0.065,1744061315.0557234,9.421514511108398,3.1415926534158336,1744061315.055725,9.421514511108398,9.840643037515031,1744061315.055727,9.421514511108398,1.4170526030878115e-20,1744061315.0557284,9.421514511108398,0.0009526874255039789,1744061315.0557306,9.421514511108398,0.0,1744061315.0557325,9.421514511108398,-22627416997.96876,1744061315.0557399,9.421514511108398,0.0,1744061315.0557423,9.421514511108398,28284271247.461903
+1744061315.0749652,9.44144082069397,-2.1765207440211434,1744061315.0749671,9.44144082069397,-9.775638520753052,1744061315.0749693,9.44144082069397,0.021416487838947597,1744061315.0749717,9.44144082069397,-56568542383.615204,1744061315.0749726,9.44144082069397,0.065,1744061315.0749743,9.44144082069397,3.1415926534158336,1744061315.074975,9.44144082069397,9.840643037515031,1744061315.074976,9.44144082069397,1.4170526030878115e-20,1744061315.074977,9.44144082069397,0.0009526874255039789,1744061315.0749784,9.44144082069397,0.0,1744061315.074979,9.44144082069397,-22627416997.96876,1744061315.07498,9.44144082069397,0.0,1744061315.0749812,9.44144082069397,28284271247.461903
+1744061315.0947006,9.46147608757019,-2.1765207440211434,1744061315.0947032,9.46147608757019,-9.775638520753052,1744061315.0947068,9.46147608757019,0.021416487838947597,1744061315.0947099,9.46147608757019,-56568542383.615204,1744061315.0947115,9.46147608757019,0.065,1744061315.0947137,9.46147608757019,3.1415926534158336,1744061315.0947156,9.46147608757019,9.840643037515031,1744061315.0947173,9.46147608757019,1.4170526030878115e-20,1744061315.094719,9.46147608757019,0.0009526874255039789,1744061315.0947208,9.46147608757019,0.0,1744061315.0947223,9.46147608757019,-22627416997.96876,1744061315.0947242,9.46147608757019,0.0,1744061315.0947256,9.46147608757019,28284271247.461903
+1744061315.1146793,9.481481075286865,-2.1765207440211434,1744061315.1146812,9.481481075286865,-9.775638520753052,1744061315.1146834,9.481481075286865,0.021416487838947597,1744061315.1146855,9.481481075286865,-56568542383.615204,1744061315.1146865,9.481481075286865,0.065,1744061315.1146877,9.481481075286865,3.1415926534158336,1744061315.1146889,9.481481075286865,9.840643037515031,1744061315.1146896,9.481481075286865,1.4170526030878115e-20,1744061315.1146905,9.481481075286865,0.0009526874255039789,1744061315.1146915,9.481481075286865,0.0,1744061315.1146927,9.481481075286865,-22627416997.96876,1744061315.1146936,9.481481075286865,0.0,1744061315.1146946,9.481481075286865,28284271247.461903
+1744061315.1350415,9.501466751098633,-2.1765207440211434,1744061315.1350431,9.501466751098633,-9.775638520753052,1744061315.135045,9.501466751098633,0.021416487838947597,1744061315.1350474,9.501466751098633,-56568542383.615204,1744061315.1350484,9.501466751098633,0.065,1744061315.1350496,9.501466751098633,3.1415926534158336,1744061315.1350505,9.501466751098633,9.840643037515031,1744061315.1350515,9.501466751098633,1.4170526030878115e-20,1744061315.1350522,9.501466751098633,0.0009526874255039789,1744061315.1350536,9.501466751098633,0.0,1744061315.1350543,9.501466751098633,-22627416997.96876,1744061315.1350553,9.501466751098633,0.0,1744061315.1350565,9.501466751098633,28284271247.461903
+1744061315.1556945,9.521614074707031,-2.1765207440211434,1744061315.1556976,9.521614074707031,-9.775638520753052,1744061315.1557004,9.521614074707031,0.021416487838947597,1744061315.1557026,9.521614074707031,-56568542383.615204,1744061315.1557035,9.521614074707031,0.065,1744061315.155705,9.521614074707031,3.1415926534158336,1744061315.1557066,9.521614074707031,9.840643037515031,1744061315.1557074,9.521614074707031,1.4170526030878115e-20,1744061315.1557083,9.521614074707031,0.0009526874255039789,1744061315.15571,9.521614074707031,0.0,1744061315.155711,9.521614074707031,-22627416997.96876,1744061315.1557124,9.521614074707031,0.0,1744061315.1557133,9.521614074707031,28284271247.461903
+1744061315.174788,9.541447162628174,-2.1765207440211434,1744061315.1747901,9.541447162628174,-9.775638520753052,1744061315.1747925,9.541447162628174,0.021416487838947597,1744061315.1747944,9.541447162628174,-56568542383.615204,1744061315.1747956,9.541447162628174,0.065,1744061315.1747968,9.541447162628174,3.1415926534158336,1744061315.1747978,9.541447162628174,9.840643037515031,1744061315.174799,9.541447162628174,1.4170526030878115e-20,1744061315.1748,9.541447162628174,0.0009526874255039789,1744061315.1748009,9.541447162628174,0.0,1744061315.1748016,9.541447162628174,-22627416997.96876,1744061315.1748028,9.541447162628174,0.0,1744061315.1748037,9.541447162628174,28284271247.461903
+1744061315.1946638,9.561444997787476,-2.1765207440211434,1744061315.1946657,9.561444997787476,-9.775638520753052,1744061315.194668,9.561444997787476,0.021416487838947597,1744061315.19467,9.561444997787476,-56568542383.615204,1744061315.1946714,9.561444997787476,0.065,1744061315.1946723,9.561444997787476,3.1415926534158336,1744061315.1946733,9.561444997787476,9.840643037515031,1744061315.1946745,9.561444997787476,1.4170526030878115e-20,1744061315.1946812,9.561444997787476,0.0009526874255039789,1744061315.1946826,9.561444997787476,0.0,1744061315.1946836,9.561444997787476,-22627416997.96876,1744061315.1946847,9.561444997787476,0.0,1744061315.1946855,9.561444997787476,28284271247.461903
+1744061315.2147524,9.581443786621094,-2.1765207440211434,1744061315.2147548,9.581443786621094,-9.775638520753052,1744061315.2147574,9.581443786621094,0.021416487838947597,1744061315.2147596,9.581443786621094,-56568542383.615204,1744061315.2147608,9.581443786621094,0.065,1744061315.214762,9.581443786621094,3.1415926534158336,1744061315.214763,9.581443786621094,9.840643037515031,1744061315.214764,9.581443786621094,1.4170526030878115e-20,1744061315.2147648,9.581443786621094,0.0009526874255039789,1744061315.214766,9.581443786621094,0.0,1744061315.2147667,9.581443786621094,-22627416997.96876,1744061315.214768,9.581443786621094,0.0,1744061315.2147686,9.581443786621094,28284271247.461903
+1744061315.2354414,9.601452350616455,-2.1765207440211434,1744061315.2354434,9.601452350616455,-9.775638520753052,1744061315.2354457,9.601452350616455,0.021416487838947597,1744061315.235448,9.601452350616455,-56568542383.615204,1744061315.2354677,9.601452350616455,0.065,1744061315.235469,9.601452350616455,3.1415926534158336,1744061315.23547,9.601452350616455,9.840643037515031,1744061315.2354708,9.601452350616455,1.4170526030878115e-20,1744061315.235472,9.601452350616455,0.0009526874255039789,1744061315.2354732,9.601452350616455,0.0,1744061315.2354739,9.601452350616455,-22627416997.96876,1744061315.2354748,9.601452350616455,0.0,1744061315.235476,9.601452350616455,28284271247.461903
+1744061315.2554429,9.62148380279541,-2.1765207440211434,1744061315.2554457,9.62148380279541,-9.775638520753052,1744061315.2554488,9.62148380279541,0.021416487838947597,1744061315.255451,9.62148380279541,-56568542383.615204,1744061315.2554522,9.62148380279541,0.065,1744061315.255472,9.62148380279541,3.1415926534158336,1744061315.255473,9.62148380279541,9.840643037515031,1744061315.255474,9.62148380279541,1.4170526030878115e-20,1744061315.255475,9.62148380279541,0.0009526874255039789,1744061315.2554762,9.62148380279541,0.0,1744061315.2554772,9.62148380279541,-22627416997.96876,1744061315.2554784,9.62148380279541,0.0,1744061315.2554793,9.62148380279541,28284271247.461903
+1744061315.2747273,9.641467332839966,-2.1765207440211434,1744061315.2747293,9.641467332839966,-9.775638520753052,1744061315.2747316,9.641467332839966,0.021416487838947597,1744061315.2747335,9.641467332839966,-56568542383.615204,1744061315.2747345,9.641467332839966,0.065,1744061315.274736,9.641467332839966,3.1415926534158336,1744061315.274737,9.641467332839966,9.840643037515031,1744061315.2747376,9.641467332839966,1.4170526030878115e-20,1744061315.2747388,9.641467332839966,0.0009526874255039789,1744061315.27474,9.641467332839966,0.0,1744061315.2747407,9.641467332839966,-22627416997.96876,1744061315.2747416,9.641467332839966,0.0,1744061315.2747426,9.641467332839966,28284271247.461903
+1744061315.2948003,9.66151475906372,-2.1765207440211434,1744061315.2948022,9.66151475906372,-9.775638520753052,1744061315.2948046,9.66151475906372,0.021416487838947597,1744061315.2948065,9.66151475906372,-56568542383.615204,1744061315.2948074,9.66151475906372,0.065,1744061315.2948089,9.66151475906372,3.1415926534158336,1744061315.2948098,9.66151475906372,9.840643037515031,1744061315.2948105,9.66151475906372,1.4170526030878115e-20,1744061315.2948117,9.66151475906372,0.0009526874255039789,1744061315.2948127,9.66151475906372,0.0,1744061315.2948136,9.66151475906372,-22627416997.96876,1744061315.2948148,9.66151475906372,0.0,1744061315.2948155,9.66151475906372,28284271247.461903
+1744061315.3147118,9.68147897720337,-2.1765207440211434,1744061315.3147137,9.68147897720337,-9.775638520753052,1744061315.314716,9.68147897720337,0.021416487838947597,1744061315.3147185,9.68147897720337,-56568542383.615204,1744061315.3147194,9.68147897720337,0.065,1744061315.3147209,9.68147897720337,3.1415926534158336,1744061315.3147218,9.68147897720337,9.840643037515031,1744061315.3147228,9.68147897720337,1.4170526030878115e-20,1744061315.3147235,9.68147897720337,0.0009526874255039789,1744061315.314725,9.68147897720337,0.0,1744061315.3147256,9.68147897720337,-22627416997.96876,1744061315.3147266,9.68147897720337,0.0,1744061315.3147278,9.68147897720337,28284271247.461903
+1744061315.335038,9.701461791992188,-2.8088035539698772,1744061315.3350399,9.701461791992188,-13.01051529547141,1744061315.3350418,9.701461791992188,0.021416487838947597,1744061315.335044,9.701461791992188,-56568542383.615204,1744061315.3350449,9.701461791992188,0.065,1744061315.335046,9.701461791992188,3.1415926533586487,1744061315.3350472,9.701461791992188,13.075510803875263,1744061315.335048,9.701461791992188,1.8828735633547913e-20,1744061315.335049,9.701461791992188,7.16213093808364e-05,1744061315.3350503,9.701461791992188,0.0,1744061315.3350513,9.701461791992188,-22627416997.96973,1744061315.3350523,9.701461791992188,0.0,1744061315.335053,9.701461791992188,28284271247.461903
+1744061315.3549619,9.721490144729614,-2.8088035539698772,1744061315.3549638,9.721490144729614,-13.01051529547141,1744061315.3549666,9.721490144729614,0.021416487838947597,1744061315.3549688,9.721490144729614,-56568542383.615204,1744061315.3549697,9.721490144729614,0.065,1744061315.3549712,9.721490144729614,3.1415926533586487,1744061315.3549721,9.721490144729614,13.075510803875263,1744061315.3549728,9.721490144729614,1.8828735633547913e-20,1744061315.354974,9.721490144729614,7.16213093808364e-05,1744061315.354975,9.721490144729614,0.0,1744061315.354976,9.721490144729614,-22627416997.969467,1744061315.3549767,9.721490144729614,0.0,1744061315.3549778,9.721490144729614,28284271247.461903
+1744061315.3755846,9.741453170776367,-2.8088035539698772,1744061315.375588,9.741453170776367,-13.01051529547141,1744061315.375592,9.741453170776367,0.021416487838947597,1744061315.3755958,9.741453170776367,-56568542383.615204,1744061315.3755977,9.741453170776367,0.065,1744061315.3756003,9.741453170776367,3.1415926533586487,1744061315.3756027,9.741453170776367,13.075510803875263,1744061315.3756044,9.741453170776367,1.8828735633547913e-20,1744061315.3756065,9.741453170776367,7.16213093808364e-05,1744061315.375609,9.741453170776367,0.0,1744061315.3756108,9.741453170776367,-22627416997.969467,1744061315.375613,9.741453170776367,0.0,1744061315.375615,9.741453170776367,28284271247.461903
+1744061315.3948624,9.761459589004517,-2.8088035539698772,1744061315.394866,9.761459589004517,-13.01051529547141,1744061315.39487,9.761459589004517,0.021416487838947597,1744061315.3948736,9.761459589004517,-56568542383.615204,1744061315.394875,9.761459589004517,0.065,1744061315.3948767,9.761459589004517,3.1415926533586487,1744061315.394878,9.761459589004517,13.075510803875263,1744061315.3948796,9.761459589004517,1.8828735633547913e-20,1744061315.3948808,9.761459589004517,7.16213093808364e-05,1744061315.3948822,9.761459589004517,0.0,1744061315.3948834,9.761459589004517,-22627416997.969467,1744061315.3948843,9.761459589004517,0.0,1744061315.3948855,9.761459589004517,28284271247.461903
+1744061315.4146945,9.781443119049072,-2.8088035539698772,1744061315.4146965,9.781443119049072,-13.01051529547141,1744061315.414699,9.781443119049072,0.021416487838947597,1744061315.4147012,9.781443119049072,-56568542383.615204,1744061315.4147027,9.781443119049072,0.065,1744061315.4147038,9.781443119049072,3.1415926533586487,1744061315.414705,9.781443119049072,13.075510803875263,1744061315.4147062,9.781443119049072,1.8828735633547913e-20,1744061315.4147072,9.781443119049072,7.16213093808364e-05,1744061315.4147081,9.781443119049072,0.0,1744061315.4147093,9.781443119049072,-22627416997.969467,1744061315.4147103,9.781443119049072,0.0,1744061315.4147112,9.781443119049072,28284271247.461903
+1744061315.4350371,9.801443099975586,-2.8088035539698772,1744061315.4350395,9.801443099975586,-13.01051529547141,1744061315.435042,9.801443099975586,0.021416487838947597,1744061315.4350438,9.801443099975586,-56568542383.615204,1744061315.4350448,9.801443099975586,0.065,1744061315.4350464,9.801443099975586,3.1415926533586487,1744061315.4350476,9.801443099975586,13.075510803875263,1744061315.4350488,9.801443099975586,1.8828735633547913e-20,1744061315.4350498,9.801443099975586,7.16213093808364e-05,1744061315.435051,9.801443099975586,0.0,1744061315.435052,9.801443099975586,-22627416997.969467,1744061315.435053,9.801443099975586,0.0,1744061315.435054,9.801443099975586,28284271247.461903
+1744061315.4547865,9.821458101272583,-2.8088035539698772,1744061315.4547887,9.821458101272583,-13.01051529547141,1744061315.454791,9.821458101272583,0.021416487838947597,1744061315.4547935,9.821458101272583,-56568542383.615204,1744061315.4547946,9.821458101272583,0.065,1744061315.4547963,9.821458101272583,3.1415926533586487,1744061315.4547973,9.821458101272583,13.075510803875263,1744061315.4547982,9.821458101272583,1.8828735633547913e-20,1744061315.4547994,9.821458101272583,7.16213093808364e-05,1744061315.4548004,9.821458101272583,0.0,1744061315.4548013,9.821458101272583,-22627416997.969467,1744061315.4548025,9.821458101272583,0.0,1744061315.4548035,9.821458101272583,28284271247.461903
+1744061315.474631,9.841443061828613,-2.8088035539698772,1744061315.4746332,9.841443061828613,-13.01051529547141,1744061315.4746356,9.841443061828613,0.021416487838947597,1744061315.4746375,9.841443061828613,-56568542383.615204,1744061315.474639,9.841443061828613,0.065,1744061315.4746401,9.841443061828613,3.1415926533586487,1744061315.474641,9.841443061828613,13.075510803875263,1744061315.4746423,9.841443061828613,1.8828735633547913e-20,1744061315.4746432,9.841443061828613,7.16213093808364e-05,1744061315.4746442,9.841443061828613,0.0,1744061315.4746451,9.841443061828613,-22627416997.969467,1744061315.4746463,9.841443061828613,0.0,1744061315.4746473,9.841443061828613,28284271247.461903
+1744061315.4951663,9.86149549484253,-2.8088035539698772,1744061315.4951682,9.86149549484253,-13.01051529547141,1744061315.4951708,9.86149549484253,0.021416487838947597,1744061315.495173,9.86149549484253,-56568542383.615204,1744061315.495174,9.86149549484253,0.065,1744061315.4951754,9.86149549484253,3.1415926533586487,1744061315.4951768,9.86149549484253,13.075510803875263,1744061315.4951777,9.86149549484253,1.8828735633547913e-20,1744061315.4951787,9.86149549484253,7.16213093808364e-05,1744061315.4951801,9.86149549484253,0.0,1744061315.495181,9.86149549484253,-22627416997.969467,1744061315.495182,9.86149549484253,0.0,1744061315.4951835,9.86149549484253,28284271247.461903
+1744061315.5145993,9.881439447402954,-2.8088035539698772,1744061315.5146012,9.881439447402954,-13.01051529547141,1744061315.5146036,9.881439447402954,0.021416487838947597,1744061315.5146058,9.881439447402954,-56568542383.615204,1744061315.514607,9.881439447402954,0.065,1744061315.5146081,9.881439447402954,3.1415926533586487,1744061315.514609,9.881439447402954,13.075510803875263,1744061315.5146098,9.881439447402954,1.8828735633547913e-20,1744061315.514611,9.881439447402954,7.16213093808364e-05,1744061315.5146122,9.881439447402954,0.0,1744061315.5146132,9.881439447402954,-22627416997.969467,1744061315.5146143,9.881439447402954,0.0,1744061315.5146153,9.881439447402954,28284271247.461903
+1744061315.5350814,9.901443243026733,-2.8088035539698772,1744061315.5350847,9.901443243026733,-13.01051529547141,1744061315.5350876,9.901443243026733,0.021416487838947597,1744061315.53509,9.901443243026733,-56568542383.615204,1744061315.5350912,9.901443243026733,0.065,1744061315.5350928,9.901443243026733,3.1415926533586487,1744061315.535094,9.901443243026733,13.075510803875263,1744061315.5350947,9.901443243026733,1.8828735633547913e-20,1744061315.5350957,9.901443243026733,7.16213093808364e-05,1744061315.535097,9.901443243026733,0.0,1744061315.5350978,9.901443243026733,-22627416997.969467,1744061315.5350988,9.901443243026733,0.0,1744061315.5351,9.901443243026733,28284271247.461903
+1744061315.5549192,9.921464681625366,-2.8088035539698772,1744061315.5549214,9.921464681625366,-13.01051529547141,1744061315.554924,9.921464681625366,0.021416487838947597,1744061315.5549262,9.921464681625366,-56568542383.615204,1744061315.5549273,9.921464681625366,0.065,1744061315.5549288,9.921464681625366,3.1415926533586487,1744061315.55493,9.921464681625366,13.075510803875263,1744061315.554931,9.921464681625366,1.8828735633547913e-20,1744061315.5549319,9.921464681625366,7.16213093808364e-05,1744061315.5549333,9.921464681625366,0.0,1744061315.5549343,9.921464681625366,-22627416997.969467,1744061315.5549352,9.921464681625366,0.0,1744061315.5549364,9.921464681625366,28284271247.461903
+1744061315.5746365,9.941430807113647,-2.8088035539698772,1744061315.5746386,9.941430807113647,-13.01051529547141,1744061315.5746408,9.941430807113647,0.021416487838947597,1744061315.574643,9.941430807113647,-56568542383.615204,1744061315.5746439,9.941430807113647,0.065,1744061315.5746455,9.941430807113647,3.1415926533586487,1744061315.5746465,9.941430807113647,13.075510803875263,1744061315.5746477,9.941430807113647,1.8828735633547913e-20,1744061315.5746484,9.941430807113647,7.16213093808364e-05,1744061315.5746496,9.941430807113647,0.0,1744061315.5746503,9.941430807113647,-22627416997.969467,1744061315.5746515,9.941430807113647,0.0,1744061315.5746524,9.941430807113647,28284271247.461903
+1744061315.594828,9.961440086364746,-2.8088035539698772,1744061315.5948296,9.961440086364746,-13.01051529547141,1744061315.594832,9.961440086364746,0.021416487838947597,1744061315.5948339,9.961440086364746,-56568542383.615204,1744061315.5948353,9.961440086364746,0.065,1744061315.5948365,9.961440086364746,3.1415926533586487,1744061315.5948374,9.961440086364746,13.075510803875263,1744061315.5948384,9.961440086364746,1.8828735633547913e-20,1744061315.5948393,9.961440086364746,7.16213093808364e-05,1744061315.5948403,9.961440086364746,0.0,1744061315.5948412,9.961440086364746,-22627416997.969467,1744061315.5948424,9.961440086364746,0.0,1744061315.5948431,9.961440086364746,28284271247.461903
+1744061315.6147168,9.981447458267212,-2.8088035539698772,1744061315.6147184,9.981447458267212,-13.01051529547141,1744061315.6147208,9.981447458267212,0.021416487838947597,1744061315.6147227,9.981447458267212,-56568542383.615204,1744061315.614724,9.981447458267212,0.065,1744061315.614725,9.981447458267212,3.1415926533586487,1744061315.614726,9.981447458267212,13.075510803875263,1744061315.6147273,9.981447458267212,1.8828735633547913e-20,1744061315.6147282,9.981447458267212,7.16213093808364e-05,1744061315.6147292,9.981447458267212,0.0,1744061315.6147304,9.981447458267212,-22627416997.969467,1744061315.6147313,9.981447458267212,0.0,1744061315.614732,9.981447458267212,28284271247.461903
+1744061315.6351132,10.001437664031982,-2.8088035539698772,1744061315.6351159,10.001437664031982,-13.01051529547141,1744061315.6351182,10.001437664031982,0.021416487838947597,1744061315.635121,10.001437664031982,-56568542383.615204,1744061315.6351225,10.001437664031982,0.065,1744061315.6351247,10.001437664031982,3.1415926533586487,1744061315.6351268,10.001437664031982,13.075510803875263,1744061315.635128,10.001437664031982,1.8828735633547913e-20,1744061315.6351295,10.001437664031982,7.16213093808364e-05,1744061315.635131,10.001437664031982,0.0,1744061315.635132,10.001437664031982,-22627416997.969467,1744061315.6351335,10.001437664031982,0.0,1744061315.6351347,10.001437664031982,28284271247.461903
+1744061315.6553056,10.021475791931152,-2.8088035539698772,1744061315.6553097,10.021475791931152,-13.01051529547141,1744061315.6553137,10.021475791931152,0.021416487838947597,1744061315.6553159,10.021475791931152,-56568542383.615204,1744061315.655318,10.021475791931152,0.065,1744061315.6553195,10.021475791931152,3.1415926533586487,1744061315.6553214,10.021475791931152,13.075510803875263,1744061315.6553226,10.021475791931152,1.8828735633547913e-20,1744061315.6553237,10.021475791931152,7.16213093808364e-05,1744061315.6553252,10.021475791931152,0.0,1744061315.6553261,10.021475791931152,-22627416997.969467,1744061315.6553273,10.021475791931152,0.0,1744061315.6553295,10.021475791931152,28284271247.461903
+1744061315.6746237,10.041443824768066,-2.8088035539698772,1744061315.6746259,10.041443824768066,-13.01051529547141,1744061315.6746278,10.041443824768066,0.021416487838947597,1744061315.67463,10.041443824768066,-56568542383.615204,1744061315.6746309,10.041443824768066,0.065,1744061315.6746323,10.041443824768066,3.1415926533586487,1744061315.6746333,10.041443824768066,13.075510803875263,1744061315.674634,10.041443824768066,1.8828735633547913e-20,1744061315.674635,10.041443824768066,7.16213093808364e-05,1744061315.6746364,10.041443824768066,0.0,1744061315.674637,10.041443824768066,-22627416997.969467,1744061315.6746383,10.041443824768066,0.0,1744061315.6746395,10.041443824768066,28284271247.461903
+1744061315.6946712,10.061446905136108,-2.8088035539698772,1744061315.6946726,10.061446905136108,-13.01051529547141,1744061315.6946752,10.061446905136108,0.021416487838947597,1744061315.6946774,10.061446905136108,-56568542383.615204,1744061315.6946785,10.061446905136108,0.065,1744061315.6946797,10.061446905136108,3.1415926533586487,1744061315.694681,10.061446905136108,13.075510803875263,1744061315.694682,10.061446905136108,1.8828735633547913e-20,1744061315.6946826,10.061446905136108,7.16213093808364e-05,1744061315.6946838,10.061446905136108,0.0,1744061315.6946847,10.061446905136108,-22627416997.969467,1744061315.6946857,10.061446905136108,0.0,1744061315.6946867,10.061446905136108,28284271247.461903
+1744061315.7147765,10.081438779830933,-2.8088035539698772,1744061315.7147791,10.081438779830933,-13.01051529547141,1744061315.7147825,10.081438779830933,0.021416487838947597,1744061315.7147849,10.081438779830933,-56568542383.615204,1744061315.714786,10.081438779830933,0.065,1744061315.7147872,10.081438779830933,3.1415926533586487,1744061315.7147887,10.081438779830933,13.075510803875263,1744061315.7147899,10.081438779830933,1.8828735633547913e-20,1744061315.714791,10.081438779830933,7.16213093808364e-05,1744061315.714793,10.081438779830933,0.0,1744061315.7147937,10.081438779830933,-22627416997.969467,1744061315.7147946,10.081438779830933,0.0,1744061315.7147963,10.081438779830933,28284271247.461903
+1744061315.7349045,10.101441383361816,-2.8088035539698772,1744061315.7349064,10.101441383361816,-13.01051529547141,1744061315.7349083,10.101441383361816,0.021416487838947597,1744061315.7349105,10.101441383361816,-56568542383.615204,1744061315.7349114,10.101441383361816,0.065,1744061315.734913,10.101441383361816,3.1415926533586487,1744061315.7349207,10.101441383361816,13.075510803875263,1744061315.7349217,10.101441383361816,1.8828735633547913e-20,1744061315.7349226,10.101441383361816,7.16213093808364e-05,1744061315.734924,10.101441383361816,0.0,1744061315.7349248,10.101441383361816,-22627416997.969467,1744061315.7349257,10.101441383361816,0.0,1744061315.734927,10.101441383361816,28284271247.461903
+1744061315.7560244,10.121527910232544,-2.8088035539698772,1744061315.7560296,10.121527910232544,-13.01051529547141,1744061315.7560356,10.121527910232544,0.021416487838947597,1744061315.7560394,10.121527910232544,-56568542383.615204,1744061315.7560413,10.121527910232544,0.065,1744061315.7560434,10.121527910232544,3.1415926533586487,1744061315.7560456,10.121527910232544,13.075510803875263,1744061315.756047,10.121527910232544,1.8828735633547913e-20,1744061315.756049,10.121527910232544,7.16213093808364e-05,1744061315.7560518,10.121527910232544,0.0,1744061315.7560534,10.121527910232544,-22627416997.969467,1744061315.756055,10.121527910232544,0.0,1744061315.7560568,10.121527910232544,28284271247.461903
+1744061315.774865,10.141470909118652,-2.8088035539698772,1744061315.7748666,10.141470909118652,-13.01051529547141,1744061315.7748747,10.141470909118652,0.021416487838947597,1744061315.774877,10.141470909118652,-56568542383.615204,1744061315.7748783,10.141470909118652,0.065,1744061315.7748795,10.141470909118652,3.1415926533586487,1744061315.774881,10.141470909118652,13.075510803875263,1744061315.7748816,10.141470909118652,1.8828735633547913e-20,1744061315.7748826,10.141470909118652,7.16213093808364e-05,1744061315.7748837,10.141470909118652,0.0,1744061315.7748847,10.141470909118652,-22627416997.969467,1744061315.774886,10.141470909118652,0.0,1744061315.7748868,10.141470909118652,28284271247.461903
+1744061315.795431,10.161479234695435,-2.8088035539698772,1744061315.795434,10.161479234695435,-13.01051529547141,1744061315.7954378,10.161479234695435,0.021416487838947597,1744061315.7954414,10.161479234695435,-56568542383.615204,1744061315.7954612,10.161479234695435,0.065,1744061315.7954633,10.161479234695435,3.1415926533586487,1744061315.795466,10.161479234695435,13.075510803875263,1744061315.7954679,10.161479234695435,1.8828735633547913e-20,1744061315.7954698,10.161479234695435,7.16213093808364e-05,1744061315.795472,10.161479234695435,0.0,1744061315.7954736,10.161479234695435,-22627416997.969467,1744061315.7954755,10.161479234695435,0.0,1744061315.795478,10.161479234695435,28284271247.461903
+1744061315.814747,10.181480884552002,-2.8088035539698772,1744061315.814749,10.181480884552002,-13.01051529547141,1744061315.8147514,10.181480884552002,0.021416487838947597,1744061315.8147535,10.181480884552002,-56568542383.615204,1744061315.8147545,10.181480884552002,0.065,1744061315.814756,10.181480884552002,3.1415926533586487,1744061315.8147569,10.181480884552002,13.075510803875263,1744061315.8147576,10.181480884552002,1.8828735633547913e-20,1744061315.8147585,10.181480884552002,7.16213093808364e-05,1744061315.8147597,10.181480884552002,0.0,1744061315.8147607,10.181480884552002,-22627416997.969467,1744061315.8147616,10.181480884552002,0.0,1744061315.8147626,10.181480884552002,28284271247.461903
+1744061315.8351774,10.201438426971436,-3.472490848303705,1744061315.835179,10.201438426971436,-16.346990143482753,1744061315.8351812,10.201438426971436,0.021416487838947597,1744061315.8351831,10.201438426971436,-56568542383.615204,1744061315.835184,10.201438426971436,0.065,1744061315.8351853,10.201438426971436,3.1415926532996674,1744061315.8351865,10.201438426971436,16.411994953873954,1744061315.8351874,10.201438426971436,2.363327282948525e-20,1744061315.8351882,10.201438426971436,4.963967532552416e-06,1744061315.8351896,10.201438426971436,0.0,1744061315.8351905,10.201438426971436,-22627416997.96954,1744061315.8351915,10.201438426971436,0.0,1744061315.8351927,10.201438426971436,28284271247.461903
+1744061315.8559287,10.221461296081543,-3.472490848303705,1744061315.8559313,10.221461296081543,-16.346990143482753,1744061315.8559353,10.221461296081543,0.021416487838947597,1744061315.855939,10.221461296081543,-56568542383.615204,1744061315.8559408,10.221461296081543,0.065,1744061315.8559434,10.221461296081543,3.1415926532996674,1744061315.8559456,10.221461296081543,16.411994953873954,1744061315.855947,10.221461296081543,2.363327282948525e-20,1744061315.8559492,10.221461296081543,4.963967532552416e-06,1744061315.8559508,10.221461296081543,0.0,1744061315.855953,10.221461296081543,-22627416997.96952,1744061315.8559546,10.221461296081543,0.0,1744061315.8559568,10.221461296081543,28284271247.461903
+1744061315.874592,10.241440534591675,-3.472490848303705,1744061315.874594,10.241440534591675,-16.346990143482753,1744061315.8745964,10.241440534591675,0.021416487838947597,1744061315.8745985,10.241440534591675,-56568542383.615204,1744061315.8745995,10.241440534591675,0.065,1744061315.8746006,10.241440534591675,3.1415926532996674,1744061315.874602,10.241440534591675,16.411994953873954,1744061315.8746028,10.241440534591675,2.363327282948525e-20,1744061315.8746037,10.241440534591675,4.963967532552416e-06,1744061315.874605,10.241440534591675,0.0,1744061315.874606,10.241440534591675,-22627416997.96952,1744061315.8746068,10.241440534591675,0.0,1744061315.8746078,10.241440534591675,28284271247.461903
+1744061315.894678,10.26145315170288,-3.472490848303705,1744061315.8946798,10.26145315170288,-16.346990143482753,1744061315.8946824,10.26145315170288,0.021416487838947597,1744061315.8946843,10.26145315170288,-56568542383.615204,1744061315.8946857,10.26145315170288,0.065,1744061315.894687,10.26145315170288,3.1415926532996674,1744061315.894688,10.26145315170288,16.411994953873954,1744061315.894689,10.26145315170288,2.363327282948525e-20,1744061315.8946898,10.26145315170288,4.963967532552416e-06,1744061315.894691,10.26145315170288,0.0,1744061315.894692,10.26145315170288,-22627416997.96952,1744061315.894693,10.26145315170288,0.0,1744061315.8946936,10.26145315170288,28284271247.461903
+1744061315.9146802,10.281473875045776,-3.472490848303705,1744061315.9146824,10.281473875045776,-16.346990143482753,1744061315.914685,10.281473875045776,0.021416487838947597,1744061315.914687,10.281473875045776,-56568542383.615204,1744061315.914688,10.281473875045776,0.065,1744061315.9146893,10.281473875045776,3.1415926532996674,1744061315.9146903,10.281473875045776,16.411994953873954,1744061315.9146912,10.281473875045776,2.363327282948525e-20,1744061315.9146922,10.281473875045776,4.963967532552416e-06,1744061315.9146934,10.281473875045776,0.0,1744061315.914694,10.281473875045776,-22627416997.96952,1744061315.9146953,10.281473875045776,0.0,1744061315.914696,10.281473875045776,28284271247.461903
+1744061315.9352796,10.301479816436768,-3.472490848303705,1744061315.935281,10.301479816436768,-16.346990143482753,1744061315.9352834,10.301479816436768,0.021416487838947597,1744061315.9352856,10.301479816436768,-56568542383.615204,1744061315.9352865,10.301479816436768,0.065,1744061315.9352877,10.301479816436768,3.1415926532996674,1744061315.935289,10.301479816436768,16.411994953873954,1744061315.9352899,10.301479816436768,2.363327282948525e-20,1744061315.9352908,10.301479816436768,4.963967532552416e-06,1744061315.935292,10.301479816436768,0.0,1744061315.9352927,10.301479816436768,-22627416997.96952,1744061315.9352937,10.301479816436768,0.0,1744061315.9352944,10.301479816436768,28284271247.461903
+1744061315.9554281,10.321471929550171,-3.472490848303705,1744061315.9554315,10.321471929550171,-16.346990143482753,1744061315.9554365,10.321471929550171,0.021416487838947597,1744061315.95544,10.321471929550171,-56568542383.615204,1744061315.955442,10.321471929550171,0.065,1744061315.9554439,10.321471929550171,3.1415926532996674,1744061315.9554458,10.321471929550171,16.411994953873954,1744061315.9554472,10.321471929550171,2.363327282948525e-20,1744061315.955449,10.321471929550171,4.963967532552416e-06,1744061315.9554513,10.321471929550171,0.0,1744061315.955453,10.321471929550171,-22627416997.96952,1744061315.955469,10.321471929550171,0.0,1744061315.9554703,10.321471929550171,28284271247.461903
+1744061315.9749696,10.341450929641724,-3.472490848303705,1744061315.974972,10.341450929641724,-16.346990143482753,1744061315.9749742,10.341450929641724,0.021416487838947597,1744061315.9749765,10.341450929641724,-56568542383.615204,1744061315.9749777,10.341450929641724,0.065,1744061315.9749792,10.341450929641724,3.1415926532996674,1744061315.97498,10.341450929641724,16.411994953873954,1744061315.9749808,10.341450929641724,2.363327282948525e-20,1744061315.9749818,10.341450929641724,4.963967532552416e-06,1744061315.974983,10.341450929641724,0.0,1744061315.9749837,10.341450929641724,-22627416997.96952,1744061315.9749846,10.341450929641724,0.0,1744061315.9749858,10.341450929641724,28284271247.461903
+1744061315.9946733,10.361443758010864,-3.472490848303705,1744061315.994675,10.361443758010864,-16.346990143482753,1744061315.9946775,10.361443758010864,0.021416487838947597,1744061315.9946795,10.361443758010864,-56568542383.615204,1744061315.9946806,10.361443758010864,0.065,1744061315.9946818,10.361443758010864,3.1415926532996674,1744061315.9946828,10.361443758010864,16.411994953873954,1744061315.994684,10.361443758010864,2.363327282948525e-20,1744061315.9946847,10.361443758010864,4.963967532552416e-06,1744061315.9946856,10.361443758010864,0.0,1744061315.9946866,10.361443758010864,-22627416997.96952,1744061315.9946878,10.361443758010864,0.0,1744061315.9946885,10.361443758010864,28284271247.461903
+1744061316.0147667,10.381452322006226,-3.472490848303705,1744061316.0147688,10.381452322006226,-16.346990143482753,1744061316.0147715,10.381452322006226,0.021416487838947597,1744061316.0147736,10.381452322006226,-56568542383.615204,1744061316.0147762,10.381452322006226,0.065,1744061316.0147777,10.381452322006226,3.1415926532996674,1744061316.0147789,10.381452322006226,16.411994953873954,1744061316.0147796,10.381452322006226,2.363327282948525e-20,1744061316.0147808,10.381452322006226,4.963967532552416e-06,1744061316.014782,10.381452322006226,0.0,1744061316.0147827,10.381452322006226,-22627416997.96952,1744061316.0147839,10.381452322006226,0.0,1744061316.0147848,10.381452322006226,28284271247.461903
+1744061316.0359335,10.401480197906494,-3.472490848303705,1744061316.035936,10.401480197906494,-16.346990143482753,1744061316.0359385,10.401480197906494,0.021416487838947597,1744061316.0359406,10.401480197906494,-56568542383.615204,1744061316.0359423,10.401480197906494,0.065,1744061316.035944,10.401480197906494,3.1415926532996674,1744061316.035945,10.401480197906494,16.411994953873954,1744061316.035946,10.401480197906494,2.363327282948525e-20,1744061316.035947,10.401480197906494,4.963967532552416e-06,1744061316.035948,10.401480197906494,0.0,1744061316.035949,10.401480197906494,-22627416997.96952,1744061316.0359502,10.401480197906494,0.0,1744061316.0359511,10.401480197906494,28284271247.461903
+1744061316.0554607,10.421557903289795,-3.472490848303705,1744061316.0554626,10.421557903289795,-16.346990143482753,1744061316.0554657,10.421557903289795,0.021416487838947597,1744061316.0554678,10.421557903289795,-56568542383.615204,1744061316.055469,10.421557903289795,0.065,1744061316.055471,10.421557903289795,3.1415926532996674,1744061316.0554721,10.421557903289795,16.411994953873954,1744061316.055473,10.421557903289795,2.363327282948525e-20,1744061316.0554745,10.421557903289795,4.963967532552416e-06,1744061316.0554755,10.421557903289795,0.0,1744061316.0554764,10.421557903289795,-22627416997.96952,1744061316.055478,10.421557903289795,0.0,1744061316.0554793,10.421557903289795,28284271247.461903
+1744061316.0747194,10.441442012786865,-3.472490848303705,1744061316.0747216,10.441442012786865,-16.346990143482753,1744061316.0747235,10.441442012786865,0.021416487838947597,1744061316.0747256,10.441442012786865,-56568542383.615204,1744061316.0747266,10.441442012786865,0.065,1744061316.074728,10.441442012786865,3.1415926532996674,1744061316.074729,10.441442012786865,16.411994953873954,1744061316.07473,10.441442012786865,2.363327282948525e-20,1744061316.0747306,10.441442012786865,4.963967532552416e-06,1744061316.074732,10.441442012786865,0.0,1744061316.0747328,10.441442012786865,-22627416997.96952,1744061316.0747337,10.441442012786865,0.0,1744061316.074735,10.441442012786865,28284271247.461903
+1744061316.0948153,10.461459875106812,-3.472490848303705,1744061316.094817,10.461459875106812,-16.346990143482753,1744061316.0948195,10.461459875106812,0.021416487838947597,1744061316.0948217,10.461459875106812,-56568542383.615204,1744061316.0948226,10.461459875106812,0.065,1744061316.0948238,10.461459875106812,3.1415926532996674,1744061316.094825,10.461459875106812,16.411994953873954,1744061316.094826,10.461459875106812,2.363327282948525e-20,1744061316.094827,10.461459875106812,4.963967532552416e-06,1744061316.0948281,10.461459875106812,0.0,1744061316.094829,10.461459875106812,-22627416997.96952,1744061316.09483,10.461459875106812,0.0,1744061316.094831,10.461459875106812,28284271247.461903
+1744061316.1146333,10.481439352035522,-3.472490848303705,1744061316.114635,10.481439352035522,-16.346990143482753,1744061316.1146374,10.481439352035522,0.021416487838947597,1744061316.1146395,10.481439352035522,-56568542383.615204,1744061316.1146407,10.481439352035522,0.065,1744061316.114642,10.481439352035522,3.1415926532996674,1744061316.1146429,10.481439352035522,16.411994953873954,1744061316.1146438,10.481439352035522,2.363327282948525e-20,1744061316.1146448,10.481439352035522,4.963967532552416e-06,1744061316.114646,10.481439352035522,0.0,1744061316.1146467,10.481439352035522,-22627416997.96952,1744061316.114648,10.481439352035522,0.0,1744061316.1146488,10.481439352035522,28284271247.461903
+1744061316.1358955,10.50145173072815,-3.472490848303705,1744061316.1358976,10.50145173072815,-16.346990143482753,1744061316.1359,10.50145173072815,0.021416487838947597,1744061316.1359022,10.50145173072815,-56568542383.615204,1744061316.1359031,10.50145173072815,0.065,1744061316.1359048,10.50145173072815,3.1415926532996674,1744061316.1359057,10.50145173072815,16.411994953873954,1744061316.135907,10.50145173072815,2.363327282948525e-20,1744061316.135908,10.50145173072815,4.963967532552416e-06,1744061316.1359088,10.50145173072815,0.0,1744061316.1359098,10.50145173072815,-22627416997.96952,1744061316.1359112,10.50145173072815,0.0,1744061316.135912,10.50145173072815,28284271247.461903
+1744061316.1547117,10.521446466445923,-3.472490848303705,1744061316.1547139,10.521446466445923,-16.346990143482753,1744061316.1547165,10.521446466445923,0.021416487838947597,1744061316.1547186,10.521446466445923,-56568542383.615204,1744061316.1547198,10.521446466445923,0.065,1744061316.154721,10.521446466445923,3.1415926532996674,1744061316.1547222,10.521446466445923,16.411994953873954,1744061316.1547234,10.521446466445923,2.363327282948525e-20,1744061316.1547244,10.521446466445923,4.963967532552416e-06,1744061316.1547256,10.521446466445923,0.0,1744061316.1547267,10.521446466445923,-22627416997.96952,1744061316.1547277,10.521446466445923,0.0,1744061316.154729,10.521446466445923,28284271247.461903
+1744061316.1747818,10.541441679000854,-3.472490848303705,1744061316.174784,10.541441679000854,-16.346990143482753,1744061316.174786,10.541441679000854,0.021416487838947597,1744061316.1747882,10.541441679000854,-56568542383.615204,1744061316.1747894,10.541441679000854,0.065,1744061316.1747906,10.541441679000854,3.1415926532996674,1744061316.174792,10.541441679000854,16.411994953873954,1744061316.1747928,10.541441679000854,2.363327282948525e-20,1744061316.1747937,10.541441679000854,4.963967532552416e-06,1744061316.174795,10.541441679000854,0.0,1744061316.174796,10.541441679000854,-22627416997.96952,1744061316.174797,10.541441679000854,0.0,1744061316.1748,10.541441679000854,28284271247.461903
+1744061316.1948466,10.561447620391846,-3.472490848303705,1744061316.194849,10.561447620391846,-16.346990143482753,1744061316.1948519,10.561447620391846,0.021416487838947597,1744061316.1948543,10.561447620391846,-56568542383.615204,1744061316.1948552,10.561447620391846,0.065,1744061316.1948566,10.561447620391846,3.1415926532996674,1744061316.194858,10.561447620391846,16.411994953873954,1744061316.194859,10.561447620391846,2.363327282948525e-20,1744061316.19486,10.561447620391846,4.963967532552416e-06,1744061316.1948614,10.561447620391846,0.0,1744061316.1948624,10.561447620391846,-22627416997.96952,1744061316.1948633,10.561447620391846,0.0,1744061316.194864,10.561447620391846,28284271247.461903
+1744061316.2146297,10.581438779830933,-3.472490848303705,1744061316.214631,10.581438779830933,-16.346990143482753,1744061316.2146335,10.581438779830933,0.021416487838947597,1744061316.2146356,10.581438779830933,-56568542383.615204,1744061316.2146366,10.581438779830933,0.065,1744061316.2146378,10.581438779830933,3.1415926532996674,1744061316.214639,10.581438779830933,16.411994953873954,1744061316.21464,10.581438779830933,2.363327282948525e-20,1744061316.2146406,10.581438779830933,4.963967532552416e-06,1744061316.2146418,10.581438779830933,0.0,1744061316.2146428,10.581438779830933,-22627416997.96952,1744061316.2146437,10.581438779830933,0.0,1744061316.2146447,10.581438779830933,28284271247.461903
+1744061316.235787,10.601452112197876,-3.472490848303705,1744061316.2357888,10.601452112197876,-16.346990143482753,1744061316.2357912,10.601452112197876,0.021416487838947597,1744061316.235793,10.601452112197876,-56568542383.615204,1744061316.235794,10.601452112197876,0.065,1744061316.2357955,10.601452112197876,3.1415926532996674,1744061316.2357965,10.601452112197876,16.411994953873954,1744061316.2357972,10.601452112197876,2.363327282948525e-20,1744061316.2357984,10.601452112197876,4.963967532552416e-06,1744061316.2357993,10.601452112197876,0.0,1744061316.2358003,10.601452112197876,-22627416997.96952,1744061316.2358015,10.601452112197876,0.0,1744061316.2358022,10.601452112197876,28284271247.461903
+1744061316.2549136,10.621509552001953,-3.472490848303705,1744061316.2549174,10.621509552001953,-16.346990143482753,1744061316.2549207,10.621509552001953,0.021416487838947597,1744061316.2549233,10.621509552001953,-56568542383.615204,1744061316.2549255,10.621509552001953,0.065,1744061316.254928,10.621509552001953,3.1415926532996674,1744061316.2549298,10.621509552001953,16.411994953873954,1744061316.2549314,10.621509552001953,2.363327282948525e-20,1744061316.2549338,10.621509552001953,4.963967532552416e-06,1744061316.2549353,10.621509552001953,0.0,1744061316.254937,10.621509552001953,-22627416997.96952,1744061316.2549384,10.621509552001953,0.0,1744061316.2549398,10.621509552001953,28284271247.461903
+1744061316.274961,10.641477584838867,-3.472490848303705,1744061316.2749627,10.641477584838867,-16.346990143482753,1744061316.2749653,10.641477584838867,0.021416487838947597,1744061316.2749672,10.641477584838867,-56568542383.615204,1744061316.2749686,10.641477584838867,0.065,1744061316.2749698,10.641477584838867,3.1415926532996674,1744061316.2749712,10.641477584838867,16.411994953873954,1744061316.2749722,10.641477584838867,2.363327282948525e-20,1744061316.2749732,10.641477584838867,4.963967532552416e-06,1744061316.2749743,10.641477584838867,0.0,1744061316.2749753,10.641477584838867,-22627416997.96952,1744061316.2749763,10.641477584838867,0.0,1744061316.2749772,10.641477584838867,28284271247.461903
+1744061316.2948399,10.661451578140259,-3.472490848303705,1744061316.2948418,10.661451578140259,-16.346990143482753,1744061316.2948449,10.661451578140259,0.021416487838947597,1744061316.2948475,10.661451578140259,-56568542383.615204,1744061316.2948484,10.661451578140259,0.065,1744061316.2948496,10.661451578140259,3.1415926532996674,1744061316.2948508,10.661451578140259,16.411994953873954,1744061316.2948515,10.661451578140259,2.363327282948525e-20,1744061316.294853,10.661451578140259,4.963967532552416e-06,1744061316.294854,10.661451578140259,0.0,1744061316.2948549,10.661451578140259,-22627416997.96952,1744061316.2948563,10.661451578140259,0.0,1744061316.2948573,10.661451578140259,28284271247.461903
+1744061316.314657,10.68143892288208,-3.472490848303705,1744061316.3146589,10.68143892288208,-16.346990143482753,1744061316.314661,10.68143892288208,0.021416487838947597,1744061316.3146632,10.68143892288208,-56568542383.615204,1744061316.3146641,10.68143892288208,0.065,1744061316.3146656,10.68143892288208,3.1415926532996674,1744061316.3146665,10.68143892288208,16.411994953873954,1744061316.3146675,10.68143892288208,2.363327282948525e-20,1744061316.3146682,10.68143892288208,4.963967532552416e-06,1744061316.3146696,10.68143892288208,0.0,1744061316.3146703,10.68143892288208,-22627416997.96952,1744061316.3146713,10.68143892288208,0.0,1744061316.3146725,10.68143892288208,28284271247.461903
+1744061316.3353148,10.70145058631897,-4.103391618603736,1744061316.3353164,10.70145058631897,-19.47575287846949,1744061316.3353186,10.70145058631897,0.021416487838947597,1744061316.3353205,10.70145058631897,-56568542383.615204,1744061316.3353217,10.70145058631897,0.065,1744061316.3353229,10.70145058631897,3.1415926532443583,1744061316.335324,10.70145058631897,19.54074959157591,1744061316.3353255,10.70145058631897,2.813867952668723e-20,1744061316.3353267,10.70145058631897,4.062451908067966e-07,1744061316.3353283,10.70145058631897,0.0,1744061316.33533,10.70145058631897,-22627416997.969524,1744061316.3353317,10.70145058631897,0.0,1744061316.3353333,10.70145058631897,28284271247.461903
+1744061316.3548892,10.72146987915039,-4.103391618603736,1744061316.3548937,10.72146987915039,-19.47575287846949,1744061316.3548975,10.72146987915039,0.021416487838947597,1744061316.3549016,10.72146987915039,-56568542383.615204,1744061316.3549035,10.72146987915039,0.065,1744061316.3549058,10.72146987915039,3.1415926532443583,1744061316.354908,10.72146987915039,19.54074959157591,1744061316.3549097,10.72146987915039,2.813867952668723e-20,1744061316.3549118,10.72146987915039,4.062451908067966e-07,1744061316.354915,10.72146987915039,0.0,1744061316.3549163,10.72146987915039,-22627416997.969524,1744061316.3549185,10.72146987915039,0.0,1744061316.35492,10.72146987915039,28284271247.461903
+1744061316.3751464,10.741446256637573,-4.103391618603736,1744061316.3751495,10.741446256637573,-19.47575287846949,1744061316.375153,10.741446256637573,0.021416487838947597,1744061316.3751569,10.741446256637573,-56568542383.615204,1744061316.3751588,10.741446256637573,0.065,1744061316.3751614,10.741446256637573,3.1415926532443583,1744061316.3751636,10.741446256637573,19.54074959157591,1744061316.3751655,10.741446256637573,2.813867952668723e-20,1744061316.3751674,10.741446256637573,4.062451908067966e-07,1744061316.3751698,10.741446256637573,0.0,1744061316.3751717,10.741446256637573,-22627416997.969524,1744061316.3751736,10.741446256637573,0.0,1744061316.3751755,10.741446256637573,28284271247.461903
+1744061316.3947427,10.761443138122559,-4.103391618603736,1744061316.3947446,10.761443138122559,-19.47575287846949,1744061316.3947468,10.761443138122559,0.021416487838947597,1744061316.394749,10.761443138122559,-56568542383.615204,1744061316.3947499,10.761443138122559,0.065,1744061316.3947513,10.761443138122559,3.1415926532443583,1744061316.3947523,10.761443138122559,19.54074959157591,1744061316.3947532,10.761443138122559,2.813867952668723e-20,1744061316.394754,10.761443138122559,4.062451908067966e-07,1744061316.3947551,10.761443138122559,0.0,1744061316.394756,10.761443138122559,-22627416997.969524,1744061316.394757,10.761443138122559,0.0,1744061316.3947582,10.761443138122559,28284271247.461903
+1744061316.4148502,10.781442642211914,-4.103391618603736,1744061316.4148521,10.781442642211914,-19.47575287846949,1744061316.4148543,10.781442642211914,0.021416487838947597,1744061316.4148564,10.781442642211914,-56568542383.615204,1744061316.4148576,10.781442642211914,0.065,1744061316.4148593,10.781442642211914,3.1415926532443583,1744061316.4148602,10.781442642211914,19.54074959157591,1744061316.4148612,10.781442642211914,2.813867952668723e-20,1744061316.4148624,10.781442642211914,4.062451908067966e-07,1744061316.4148633,10.781442642211914,0.0,1744061316.4148643,10.781442642211914,-22627416997.969524,1744061316.4148653,10.781442642211914,0.0,1744061316.4148662,10.781442642211914,28284271247.461903
+1744061316.4353843,10.801478385925293,-4.103391618603736,1744061316.4353862,10.801478385925293,-19.47575287846949,1744061316.4353883,10.801478385925293,0.021416487838947597,1744061316.4353905,10.801478385925293,-56568542383.615204,1744061316.4353917,10.801478385925293,0.065,1744061316.4353929,10.801478385925293,3.1415926532443583,1744061316.4353938,10.801478385925293,19.54074959157591,1744061316.4353948,10.801478385925293,2.813867952668723e-20,1744061316.4353955,10.801478385925293,4.062451908067966e-07,1744061316.435397,10.801478385925293,0.0,1744061316.4353976,10.801478385925293,-22627416997.969524,1744061316.4353986,10.801478385925293,0.0,1744061316.4353998,10.801478385925293,28284271247.461903
+1744061316.4551404,10.821503400802612,-4.103391618603736,1744061316.4551423,10.821503400802612,-19.47575287846949,1744061316.455145,10.821503400802612,0.021416487838947597,1744061316.4551473,10.821503400802612,-56568542383.615204,1744061316.4551482,10.821503400802612,0.065,1744061316.4551497,10.821503400802612,3.1415926532443583,1744061316.4551508,10.821503400802612,19.54074959157591,1744061316.4551516,10.821503400802612,2.813867952668723e-20,1744061316.4551528,10.821503400802612,4.062451908067966e-07,1744061316.455154,10.821503400802612,0.0,1744061316.4551547,10.821503400802612,-22627416997.969524,1744061316.4551556,10.821503400802612,0.0,1744061316.4551568,10.821503400802612,28284271247.461903
+1744061316.4746323,10.841443300247192,-4.103391618603736,1744061316.4746337,10.841443300247192,-19.47575287846949,1744061316.474636,10.841443300247192,0.021416487838947597,1744061316.474638,10.841443300247192,-56568542383.615204,1744061316.4746392,10.841443300247192,0.065,1744061316.4746404,10.841443300247192,3.1415926532443583,1744061316.4746413,10.841443300247192,19.54074959157591,1744061316.4746425,10.841443300247192,2.813867952668723e-20,1744061316.4746432,10.841443300247192,4.062451908067966e-07,1744061316.4746442,10.841443300247192,0.0,1744061316.4746451,10.841443300247192,-22627416997.969524,1744061316.4746466,10.841443300247192,0.0,1744061316.4746473,10.841443300247192,28284271247.461903
+1744061316.495049,10.86144471168518,-4.103391618603736,1744061316.4950507,10.86144471168518,-19.47575287846949,1744061316.495053,10.86144471168518,0.021416487838947597,1744061316.4950552,10.86144471168518,-56568542383.615204,1744061316.4950562,10.86144471168518,0.065,1744061316.4950573,10.86144471168518,3.1415926532443583,1744061316.4950588,10.86144471168518,19.54074959157591,1744061316.4950595,10.86144471168518,2.813867952668723e-20,1744061316.4950604,10.86144471168518,4.062451908067966e-07,1744061316.4950614,10.86144471168518,0.0,1744061316.4950626,10.86144471168518,-22627416997.969524,1744061316.4950633,10.86144471168518,0.0,1744061316.4950643,10.86144471168518,28284271247.461903
+1744061316.514692,10.881441116333008,-4.103391618603736,1744061316.5146952,10.881441116333008,-19.47575287846949,1744061316.514699,10.881441116333008,0.021416487838947597,1744061316.5147018,10.881441116333008,-56568542383.615204,1744061316.514703,10.881441116333008,0.065,1744061316.5147045,10.881441116333008,3.1415926532443583,1744061316.5147057,10.881441116333008,19.54074959157591,1744061316.5147064,10.881441116333008,2.813867952668723e-20,1744061316.5147078,10.881441116333008,4.062451908067966e-07,1744061316.5147088,10.881441116333008,0.0,1744061316.5147095,10.881441116333008,-22627416997.969524,1744061316.5147104,10.881441116333008,0.0,1744061316.5147116,10.881441116333008,28284271247.461903
+1744061316.534977,10.901466131210327,-4.103391618603736,1744061316.5349786,10.901466131210327,-19.47575287846949,1744061316.5349808,10.901466131210327,0.021416487838947597,1744061316.534983,10.901466131210327,-56568542383.615204,1744061316.534984,10.901466131210327,0.065,1744061316.5349853,10.901466131210327,3.1415926532443583,1744061316.5349865,10.901466131210327,19.54074959157591,1744061316.5349872,10.901466131210327,2.813867952668723e-20,1744061316.5349884,10.901466131210327,4.062451908067966e-07,1744061316.5349894,10.901466131210327,0.0,1744061316.5349903,10.901466131210327,-22627416997.969524,1744061316.5349913,10.901466131210327,0.0,1744061316.5349925,10.901466131210327,28284271247.461903
+1744061316.5555801,10.921499729156494,-4.103391618603736,1744061316.5555828,10.921499729156494,-19.47575287846949,1744061316.5555854,10.921499729156494,0.021416487838947597,1744061316.555588,10.921499729156494,-56568542383.615204,1744061316.5555894,10.921499729156494,0.065,1744061316.5555909,10.921499729156494,3.1415926532443583,1744061316.5555925,10.921499729156494,19.54074959157591,1744061316.5555935,10.921499729156494,2.813867952668723e-20,1744061316.5555947,10.921499729156494,4.062451908067966e-07,1744061316.5555964,10.921499729156494,0.0,1744061316.5555973,10.921499729156494,-22627416997.969524,1744061316.5555983,10.921499729156494,0.0,1744061316.5555995,10.921499729156494,28284271247.461903
+1744061316.5748665,10.94145917892456,-4.103391618603736,1744061316.574868,10.94145917892456,-19.47575287846949,1744061316.5748703,10.94145917892456,0.021416487838947597,1744061316.574874,10.94145917892456,-56568542383.615204,1744061316.5748749,10.94145917892456,0.065,1744061316.574876,10.94145917892456,3.1415926532443583,1744061316.5748773,10.94145917892456,19.54074959157591,1744061316.5748782,10.94145917892456,2.813867952668723e-20,1744061316.5748792,10.94145917892456,4.062451908067966e-07,1744061316.5748804,10.94145917892456,0.0,1744061316.5748813,10.94145917892456,-22627416997.969524,1744061316.5748823,10.94145917892456,0.0,1744061316.574883,10.94145917892456,28284271247.461903
+1744061316.5946786,10.961441040039062,-4.103391618603736,1744061316.5946805,10.961441040039062,-19.47575287846949,1744061316.594683,10.961441040039062,0.021416487838947597,1744061316.5946848,10.961441040039062,-56568542383.615204,1744061316.594686,10.961441040039062,0.065,1744061316.5946872,10.961441040039062,3.1415926532443583,1744061316.5946882,10.961441040039062,19.54074959157591,1744061316.5946891,10.961441040039062,2.813867952668723e-20,1744061316.59469,10.961441040039062,4.062451908067966e-07,1744061316.5946913,10.961441040039062,0.0,1744061316.5946925,10.961441040039062,-22627416997.969524,1744061316.5946934,10.961441040039062,0.0,1744061316.5946941,10.961441040039062,28284271247.461903
+1744061316.6146803,10.981449127197266,-4.103391618603736,1744061316.6146822,10.981449127197266,-19.47575287846949,1744061316.6146843,10.981449127197266,0.021416487838947597,1744061316.6146865,10.981449127197266,-56568542383.615204,1744061316.6146877,10.981449127197266,0.065,1744061316.6146889,10.981449127197266,3.1415926532443583,1744061316.6146898,10.981449127197266,19.54074959157591,1744061316.6146908,10.981449127197266,2.813867952668723e-20,1744061316.6146917,10.981449127197266,4.062451908067966e-07,1744061316.614693,10.981449127197266,0.0,1744061316.6146939,10.981449127197266,-22627416997.969524,1744061316.6146946,10.981449127197266,0.0,1744061316.6146958,10.981449127197266,28284271247.461903
+1744061316.634832,11.001440048217773,-4.103391618603736,1744061316.6348336,11.001440048217773,-19.47575287846949,1744061316.6348357,11.001440048217773,0.021416487838947597,1744061316.6348379,11.001440048217773,-56568542383.615204,1744061316.6348388,11.001440048217773,0.065,1744061316.63484,11.001440048217773,3.1415926532443583,1744061316.6348412,11.001440048217773,19.54074959157591,1744061316.634842,11.001440048217773,2.813867952668723e-20,1744061316.6348429,11.001440048217773,4.062451908067966e-07,1744061316.6348438,11.001440048217773,0.0,1744061316.634845,11.001440048217773,-22627416997.969524,1744061316.634846,11.001440048217773,0.0,1744061316.6348467,11.001440048217773,28284271247.461903
+1744061316.6554298,11.021490573883057,-4.103391618603736,1744061316.6554334,11.021490573883057,-19.47575287846949,1744061316.6554372,11.021490573883057,0.021416487838947597,1744061316.655441,11.021490573883057,-56568542383.615204,1744061316.655443,11.021490573883057,0.065,1744061316.6554453,11.021490573883057,3.1415926532443583,1744061316.655447,11.021490573883057,19.54074959157591,1744061316.6554487,11.021490573883057,2.813867952668723e-20,1744061316.6554503,11.021490573883057,4.062451908067966e-07,1744061316.6554525,11.021490573883057,0.0,1744061316.6554542,11.021490573883057,-22627416997.969524,1744061316.6554563,11.021490573883057,0.0,1744061316.655458,11.021490573883057,28284271247.461903
+1744061316.6747892,11.041540145874023,-4.103391618603736,1744061316.6747909,11.041540145874023,-19.47575287846949,1744061316.6747932,11.041540145874023,0.021416487838947597,1744061316.6747956,11.041540145874023,-56568542383.615204,1744061316.6747966,11.041540145874023,0.065,1744061316.6747978,11.041540145874023,3.1415926532443583,1744061316.674799,11.041540145874023,19.54074959157591,1744061316.6748,11.041540145874023,2.813867952668723e-20,1744061316.6748006,11.041540145874023,4.062451908067966e-07,1744061316.6748016,11.041540145874023,0.0,1744061316.6748028,11.041540145874023,-22627416997.969524,1744061316.6748037,11.041540145874023,0.0,1744061316.6748044,11.041540145874023,28284271247.461903
+1744061316.6946962,11.061441421508789,-4.103391618603736,1744061316.6946983,11.061441421508789,-19.47575287846949,1744061316.6947005,11.061441421508789,0.021416487838947597,1744061316.694708,11.061441421508789,-56568542383.615204,1744061316.6947095,11.061441421508789,0.065,1744061316.6947107,11.061441421508789,3.1415926532443583,1744061316.694712,11.061441421508789,19.54074959157591,1744061316.6947129,11.061441421508789,2.813867952668723e-20,1744061316.6947138,11.061441421508789,4.062451908067966e-07,1744061316.6947148,11.061441421508789,0.0,1744061316.694716,11.061441421508789,-22627416997.969524,1744061316.6947167,11.061441421508789,0.0,1744061316.6947176,11.061441421508789,28284271247.461903
+1744061316.7146695,11.081441879272461,-4.103391618603736,1744061316.7146714,11.081441879272461,-19.47575287846949,1744061316.7146738,11.081441879272461,0.021416487838947597,1744061316.714676,11.081441879272461,-56568542383.615204,1744061316.714677,11.081441879272461,0.065,1744061316.7146783,11.081441879272461,3.1415926532443583,1744061316.714679,11.081441879272461,19.54074959157591,1744061316.71468,11.081441879272461,2.813867952668723e-20,1744061316.714681,11.081441879272461,4.062451908067966e-07,1744061316.714682,11.081441879272461,0.0,1744061316.7146828,11.081441879272461,-22627416997.969524,1744061316.7146842,11.081441879272461,0.0,1744061316.714685,11.081441879272461,28284271247.461903
+1744061316.7353234,11.101440191268921,-4.103391618603736,1744061316.735325,11.101440191268921,-19.47575287846949,1744061316.7353275,11.101440191268921,0.021416487838947597,1744061316.7353296,11.101440191268921,-56568542383.615204,1744061316.7353306,11.101440191268921,0.065,1744061316.7353318,11.101440191268921,3.1415926532443583,1744061316.735333,11.101440191268921,19.54074959157591,1744061316.7353337,11.101440191268921,2.813867952668723e-20,1744061316.7353346,11.101440191268921,4.062451908067966e-07,1744061316.7353356,11.101440191268921,0.0,1744061316.7353368,11.101440191268921,-22627416997.969524,1744061316.7353377,11.101440191268921,0.0,1744061316.7353384,11.101440191268921,28284271247.461903
+1744061316.755226,11.121491432189941,-4.103391618603736,1744061316.7552292,11.121491432189941,-19.47575287846949,1744061316.75525,11.121491432189941,0.021416487838947597,1744061316.7552528,11.121491432189941,-56568542383.615204,1744061316.755255,11.121491432189941,0.065,1744061316.7552571,11.121491432189941,3.1415926532443583,1744061316.755259,11.121491432189941,19.54074959157591,1744061316.7552607,11.121491432189941,2.813867952668723e-20,1744061316.7552621,11.121491432189941,4.062451908067966e-07,1744061316.755264,11.121491432189941,0.0,1744061316.7552655,11.121491432189941,-22627416997.969524,1744061316.7552667,11.121491432189941,0.0,1744061316.755268,11.121491432189941,28284271247.461903
+1744061316.774772,11.141449689865112,-4.103391618603736,1744061316.774774,11.141449689865112,-19.47575287846949,1744061316.7747762,11.141449689865112,0.021416487838947597,1744061316.7747805,11.141449689865112,-56568542383.615204,1744061316.7747817,11.141449689865112,0.065,1744061316.774783,11.141449689865112,3.1415926532443583,1744061316.774784,11.141449689865112,19.54074959157591,1744061316.7747848,11.141449689865112,2.813867952668723e-20,1744061316.7747858,11.141449689865112,4.062451908067966e-07,1744061316.7747867,11.141449689865112,0.0,1744061316.774788,11.141449689865112,-22627416997.969524,1744061316.7747886,11.141449689865112,0.0,1744061316.7747896,11.141449689865112,28284271247.461903
+1744061316.794809,11.161449432373047,-4.103391618603736,1744061316.7948117,11.161449432373047,-19.47575287846949,1744061316.7948139,11.161449432373047,0.021416487838947597,1744061316.7948163,11.161449432373047,-56568542383.615204,1744061316.7948172,11.161449432373047,0.065,1744061316.7948189,11.161449432373047,3.1415926532443583,1744061316.7948198,11.161449432373047,19.54074959157591,1744061316.794821,11.161449432373047,2.813867952668723e-20,1744061316.794822,11.161449432373047,4.062451908067966e-07,1744061316.7948232,11.161449432373047,0.0,1744061316.7948241,11.161449432373047,-22627416997.969524,1744061316.7948253,11.161449432373047,0.0,1744061316.794826,11.161449432373047,28284271247.461903
+1744061316.8147752,11.181451797485352,-4.103391618603736,1744061316.8147776,11.181451797485352,-19.47575287846949,1744061316.8147802,11.181451797485352,0.021416487838947597,1744061316.8147824,11.181451797485352,-56568542383.615204,1744061316.8147836,11.181451797485352,0.065,1744061316.8147848,11.181451797485352,3.1415926532443583,1744061316.814786,11.181451797485352,19.54074959157591,1744061316.8147871,11.181451797485352,2.813867952668723e-20,1744061316.814788,11.181451797485352,4.062451908067966e-07,1744061316.8147893,11.181451797485352,0.0,1744061316.8147902,11.181451797485352,-22627416997.969524,1744061316.8147912,11.181451797485352,0.0,1744061316.8147922,11.181451797485352,28284271247.461903
+1744061316.8352427,11.20144248008728,-4.634957175230617,1744061316.8352447,11.20144248008728,-22.219071277931977,1744061316.835247,11.20144248008728,0.021416487838947597,1744061316.8352492,11.20144248008728,-56568542383.615204,1744061316.8352501,11.20144248008728,0.065,1744061316.8352518,11.20144248008728,3.141592653195863,1744061316.8352528,11.20144248008728,22.284065372540528,1744061316.8352537,11.20144248008728,3.208905426799857e-20,1744061316.8352547,11.20144248008728,4.525459766261869e-08,1744061316.8352559,11.20144248008728,0.0,1744061316.8352568,11.20144248008728,-22627416997.969524,1744061316.8352578,11.20144248008728,0.0,1744061316.835259,11.20144248008728,28284271247.461903
+1744061316.854892,11.221475839614868,-4.634957175230617,1744061316.8548942,11.221475839614868,-22.219071277931977,1744061316.8548965,11.221475839614868,0.021416487838947597,1744061316.854899,11.221475839614868,-56568542383.615204,1744061316.8549,11.221475839614868,0.065,1744061316.8549013,11.221475839614868,3.141592653195863,1744061316.8549023,11.221475839614868,22.284065372540528,1744061316.854903,11.221475839614868,3.208905426799857e-20,1744061316.8549056,11.221475839614868,4.525459766261869e-08,1744061316.8549068,11.221475839614868,0.0,1744061316.8549078,11.221475839614868,-22627416997.969524,1744061316.854909,11.221475839614868,0.0,1744061316.8549097,11.221475839614868,28284271247.461903
+1744061316.8746972,11.241440534591675,-4.634957175230617,1744061316.874699,11.241440534591675,-22.219071277931977,1744061316.8747015,11.241440534591675,0.021416487838947597,1744061316.874704,11.241440534591675,-56568542383.615204,1744061316.874705,11.241440534591675,0.065,1744061316.8747065,11.241440534591675,3.141592653195863,1744061316.8747075,11.241440534591675,22.284065372540528,1744061316.8747082,11.241440534591675,3.208905426799857e-20,1744061316.8747091,11.241440534591675,4.525459766261869e-08,1744061316.8747103,11.241440534591675,0.0,1744061316.874711,11.241440534591675,-22627416997.969524,1744061316.874712,11.241440534591675,0.0,1744061316.8747132,11.241440534591675,28284271247.461903
+1744061316.8946702,11.261441469192505,-4.634957175230617,1744061316.8946722,11.261441469192505,-22.219071277931977,1744061316.894674,11.261441469192505,0.021416487838947597,1744061316.8946762,11.261441469192505,-56568542383.615204,1744061316.8946774,11.261441469192505,0.065,1744061316.8946788,11.261441469192505,3.141592653195863,1744061316.8946798,11.261441469192505,22.284065372540528,1744061316.8946807,11.261441469192505,3.208905426799857e-20,1744061316.894682,11.261441469192505,4.525459766261869e-08,1744061316.894683,11.261441469192505,0.0,1744061316.8946838,11.261441469192505,-22627416997.969524,1744061316.8946846,11.261441469192505,0.0,1744061316.8946857,11.261441469192505,28284271247.461903
+1744061316.9146457,11.281439065933228,-4.634957175230617,1744061316.9146476,11.281439065933228,-22.219071277931977,1744061316.91465,11.281439065933228,0.021416487838947597,1744061316.914652,11.281439065933228,-56568542383.615204,1744061316.9146533,11.281439065933228,0.065,1744061316.9146547,11.281439065933228,3.141592653195863,1744061316.9146557,11.281439065933228,22.284065372540528,1744061316.9146564,11.281439065933228,3.208905426799857e-20,1744061316.9146576,11.281439065933228,4.525459766261869e-08,1744061316.9146585,11.281439065933228,0.0,1744061316.9146595,11.281439065933228,-22627416997.969524,1744061316.9146607,11.281439065933228,0.0,1744061316.914662,11.281439065933228,28284271247.461903
+1744061316.935835,11.301838874816895,-4.634957175230617,1744061316.9358366,11.301838874816895,-22.219071277931977,1744061316.935839,11.301838874816895,0.021416487838947597,1744061316.935841,11.301838874816895,-56568542383.615204,1744061316.935842,11.301838874816895,0.065,1744061316.9358616,11.301838874816895,3.141592653195863,1744061316.9358625,11.301838874816895,22.284065372540528,1744061316.9358635,11.301838874816895,3.208905426799857e-20,1744061316.9358647,11.301838874816895,4.525459766261869e-08,1744061316.935866,11.301838874816895,0.0,1744061316.935867,11.301838874816895,-22627416997.969524,1744061316.9358678,11.301838874816895,0.0,1744061316.935869,11.301838874816895,28284271247.461903
+1744061316.9549422,11.321466445922852,-4.634957175230617,1744061316.9549446,11.321466445922852,-22.219071277931977,1744061316.9549468,11.321466445922852,0.021416487838947597,1744061316.9549491,11.321466445922852,-56568542383.615204,1744061316.95495,11.321466445922852,0.065,1744061316.9549515,11.321466445922852,3.141592653195863,1744061316.9549527,11.321466445922852,22.284065372540528,1744061316.9549534,11.321466445922852,3.208905426799857e-20,1744061316.9549544,11.321466445922852,4.525459766261869e-08,1744061316.9549556,11.321466445922852,0.0,1744061316.9549565,11.321466445922852,-22627416997.969524,1744061316.9549575,11.321466445922852,0.0,1744061316.9549584,11.321466445922852,28284271247.461903
+1744061316.9752636,11.341454267501831,-4.634957175230617,1744061316.9752662,11.341454267501831,-22.219071277931977,1744061316.975269,11.341454267501831,0.021416487838947597,1744061316.9752715,11.341454267501831,-56568542383.615204,1744061316.9752727,11.341454267501831,0.065,1744061316.9752743,11.341454267501831,3.141592653195863,1744061316.9752755,11.341454267501831,22.284065372540528,1744061316.9752765,11.341454267501831,3.208905426799857e-20,1744061316.9752781,11.341454267501831,4.525459766261869e-08,1744061316.9752796,11.341454267501831,0.0,1744061316.975281,11.341454267501831,-22627416997.969524,1744061316.9752822,11.341454267501831,0.0,1744061316.9752834,11.341454267501831,28284271247.461903
+1744061316.994751,11.361449956893921,-4.634957175230617,1744061316.9947531,11.361449956893921,-22.219071277931977,1744061316.9947553,11.361449956893921,0.021416487838947597,1744061316.9947574,11.361449956893921,-56568542383.615204,1744061316.9947586,11.361449956893921,0.065,1744061316.9947598,11.361449956893921,3.141592653195863,1744061316.9947608,11.361449956893921,22.284065372540528,1744061316.9947617,11.361449956893921,3.208905426799857e-20,1744061316.9947627,11.361449956893921,4.525459766261869e-08,1744061316.9947639,11.361449956893921,0.0,1744061316.9947648,11.361449956893921,-22627416997.969524,1744061316.9947658,11.361449956893921,0.0,1744061316.994767,11.361449956893921,28284271247.461903
+1744061317.014889,11.3814537525177,-4.634957175230617,1744061317.0148916,11.3814537525177,-22.219071277931977,1744061317.014894,11.3814537525177,0.021416487838947597,1744061317.0148964,11.3814537525177,-56568542383.615204,1744061317.0148973,11.3814537525177,0.065,1744061317.014899,11.3814537525177,3.141592653195863,1744061317.0149002,11.3814537525177,22.284065372540528,1744061317.014901,11.3814537525177,3.208905426799857e-20,1744061317.014902,11.3814537525177,4.525459766261869e-08,1744061317.014903,11.3814537525177,0.0,1744061317.014904,11.3814537525177,-22627416997.969524,1744061317.014905,11.3814537525177,0.0,1744061317.0149062,11.3814537525177,28284271247.461903
+1744061317.035295,11.401519536972046,-4.634957175230617,1744061317.0352974,11.401519536972046,-22.219071277931977,1744061317.0352998,11.401519536972046,0.021416487838947597,1744061317.0353022,11.401519536972046,-56568542383.615204,1744061317.035303,11.401519536972046,0.065,1744061317.0353045,11.401519536972046,3.141592653195863,1744061317.0353057,11.401519536972046,22.284065372540528,1744061317.0353065,11.401519536972046,3.208905426799857e-20,1744061317.0353074,11.401519536972046,4.525459766261869e-08,1744061317.0353088,11.401519536972046,0.0,1744061317.0353098,11.401519536972046,-22627416997.969524,1744061317.0353107,11.401519536972046,0.0,1744061317.0353117,11.401519536972046,28284271247.461903
+1744061317.054869,11.421467781066895,-4.634957175230617,1744061317.0548708,11.421467781066895,-22.219071277931977,1744061317.0548737,11.421467781066895,0.021416487838947597,1744061317.0548756,11.421467781066895,-56568542383.615204,1744061317.054877,11.421467781066895,0.065,1744061317.0548782,11.421467781066895,3.141592653195863,1744061317.0548792,11.421467781066895,22.284065372540528,1744061317.0548801,11.421467781066895,3.208905426799857e-20,1744061317.0548813,11.421467781066895,4.525459766261869e-08,1744061317.0548825,11.421467781066895,0.0,1744061317.0548832,11.421467781066895,-22627416997.969524,1744061317.0548847,11.421467781066895,0.0,1744061317.0548854,11.421467781066895,28284271247.461903
+1744061317.0747385,11.441442728042603,-4.634957175230617,1744061317.074741,11.441442728042603,-22.219071277931977,1744061317.0747433,11.441442728042603,0.021416487838947597,1744061317.0747457,11.441442728042603,-56568542383.615204,1744061317.0747468,11.441442728042603,0.065,1744061317.0747483,11.441442728042603,3.141592653195863,1744061317.0747492,11.441442728042603,22.284065372540528,1744061317.07475,11.441442728042603,3.208905426799857e-20,1744061317.074751,11.441442728042603,4.525459766261869e-08,1744061317.074752,11.441442728042603,0.0,1744061317.074753,11.441442728042603,-22627416997.969524,1744061317.0747538,11.441442728042603,0.0,1744061317.0747547,11.441442728042603,28284271247.461903
+1744061317.0951624,11.461472988128662,-4.634957175230617,1744061317.0951655,11.461472988128662,-22.219071277931977,1744061317.0951684,11.461472988128662,0.021416487838947597,1744061317.0951703,11.461472988128662,-56568542383.615204,1744061317.0951717,11.461472988128662,0.065,1744061317.0951726,11.461472988128662,3.141592653195863,1744061317.095174,11.461472988128662,22.284065372540528,1744061317.095175,11.461472988128662,3.208905426799857e-20,1744061317.0951765,11.461472988128662,4.525459766261869e-08,1744061317.0951777,11.461472988128662,0.0,1744061317.0951786,11.461472988128662,-22627416997.969524,1744061317.0951798,11.461472988128662,0.0,1744061317.0951807,11.461472988128662,28284271247.461903
+1744061317.1146498,11.481441497802734,-4.634957175230617,1744061317.1146517,11.481441497802734,-22.219071277931977,1744061317.114654,11.481441497802734,0.021416487838947597,1744061317.114656,11.481441497802734,-56568542383.615204,1744061317.1146572,11.481441497802734,0.065,1744061317.1146588,11.481441497802734,3.141592653195863,1744061317.11466,11.481441497802734,22.284065372540528,1744061317.114661,11.481441497802734,3.208905426799857e-20,1744061317.114662,11.481441497802734,4.525459766261869e-08,1744061317.114663,11.481441497802734,0.0,1744061317.1146638,11.481441497802734,-22627416997.969524,1744061317.114665,11.481441497802734,0.0,1744061317.114666,11.481441497802734,28284271247.461903
+1744061317.1355925,11.501461744308472,-4.634957175230617,1744061317.1356115,11.501461744308472,-22.219071277931977,1744061317.135614,11.501461744308472,0.021416487838947597,1744061317.1356163,11.501461744308472,-56568542383.615204,1744061317.1356173,11.501461744308472,0.065,1744061317.1356184,11.501461744308472,3.141592653195863,1744061317.1356196,11.501461744308472,22.284065372540528,1744061317.1356204,11.501461744308472,3.208905426799857e-20,1744061317.1356213,11.501461744308472,4.525459766261869e-08,1744061317.1356225,11.501461744308472,0.0,1744061317.1356235,11.501461744308472,-22627416997.969524,1744061317.1356244,11.501461744308472,0.0,1744061317.1356254,11.501461744308472,28284271247.461903
+1744061317.1553333,11.521477937698364,-4.634957175230617,1744061317.1553357,11.521477937698364,-22.219071277931977,1744061317.155339,11.521477937698364,0.021416487838947597,1744061317.1553419,11.521477937698364,-56568542383.615204,1744061317.1553433,11.521477937698364,0.065,1744061317.1553452,11.521477937698364,3.141592653195863,1744061317.1553466,11.521477937698364,22.284065372540528,1744061317.155348,11.521477937698364,3.208905426799857e-20,1744061317.1553495,11.521477937698364,4.525459766261869e-08,1744061317.1553507,11.521477937698364,0.0,1744061317.1553524,11.521477937698364,-22627416997.969524,1744061317.1553538,11.521477937698364,0.0,1744061317.1553555,11.521477937698364,28284271247.461903
+1744061317.1748006,11.541453123092651,-4.634957175230617,1744061317.1748025,11.541453123092651,-22.219071277931977,1744061317.1748047,11.541453123092651,0.021416487838947597,1744061317.174807,11.541453123092651,-56568542383.615204,1744061317.174808,11.541453123092651,0.065,1744061317.1748095,11.541453123092651,3.141592653195863,1744061317.1748104,11.541453123092651,22.284065372540528,1744061317.1748111,11.541453123092651,3.208905426799857e-20,1744061317.174812,11.541453123092651,4.525459766261869e-08,1744061317.1748135,11.541453123092651,0.0,1744061317.1748142,11.541453123092651,-22627416997.969524,1744061317.1748152,11.541453123092651,0.0,1744061317.1748164,11.541453123092651,28284271247.461903
+1744061317.1948278,11.561470746994019,-4.634957175230617,1744061317.1948295,11.561470746994019,-22.219071277931977,1744061317.1948318,11.561470746994019,0.021416487838947597,1744061317.194834,11.561470746994019,-56568542383.615204,1744061317.194835,11.561470746994019,0.065,1744061317.1948361,11.561470746994019,3.141592653195863,1744061317.1948376,11.561470746994019,22.284065372540528,1744061317.1948383,11.561470746994019,3.208905426799857e-20,1744061317.1948392,11.561470746994019,4.525459766261869e-08,1744061317.1948404,11.561470746994019,0.0,1744061317.1948411,11.561470746994019,-22627416997.969524,1744061317.194842,11.561470746994019,0.0,1744061317.194843,11.561470746994019,28284271247.461903
+1744061317.2151403,11.581443071365356,-4.634957175230617,1744061317.215143,11.581443071365356,-22.219071277931977,1744061317.2151463,11.581443071365356,0.021416487838947597,1744061317.2151499,11.581443071365356,-56568542383.615204,1744061317.2151515,11.581443071365356,0.065,1744061317.215154,11.581443071365356,3.141592653195863,1744061317.215156,11.581443071365356,22.284065372540528,1744061317.2151577,11.581443071365356,3.208905426799857e-20,1744061317.2151597,11.581443071365356,4.525459766261869e-08,1744061317.2151616,11.581443071365356,0.0,1744061317.2151635,11.581443071365356,-22627416997.969524,1744061317.2151656,11.581443071365356,0.0,1744061317.2151675,11.581443071365356,28284271247.461903
+1744061317.2348776,11.601438999176025,-4.634957175230617,1744061317.2348795,11.601438999176025,-22.219071277931977,1744061317.2348819,11.601438999176025,0.021416487838947597,1744061317.2348838,11.601438999176025,-56568542383.615204,1744061317.2348852,11.601438999176025,0.065,1744061317.2348864,11.601438999176025,3.141592653195863,1744061317.2348874,11.601438999176025,22.284065372540528,1744061317.234888,11.601438999176025,3.208905426799857e-20,1744061317.2348893,11.601438999176025,4.525459766261869e-08,1744061317.2348902,11.601438999176025,0.0,1744061317.2348912,11.601438999176025,-22627416997.969524,1744061317.2348921,11.601438999176025,0.0,1744061317.234893,11.601438999176025,28284271247.461903
+1744061317.255484,11.621553897857666,-4.634957175230617,1744061317.255487,11.621553897857666,-22.219071277931977,1744061317.2554898,11.621553897857666,0.021416487838947597,1744061317.2554922,11.621553897857666,-56568542383.615204,1744061317.2554934,11.621553897857666,0.065,1744061317.2554946,11.621553897857666,3.141592653195863,1744061317.255496,11.621553897857666,22.284065372540528,1744061317.2554967,11.621553897857666,3.208905426799857e-20,1744061317.255498,11.621553897857666,4.525459766261869e-08,1744061317.2554991,11.621553897857666,0.0,1744061317.2555,11.621553897857666,-22627416997.969524,1744061317.255501,11.621553897857666,0.0,1744061317.255502,11.621553897857666,28284271247.461903
+1744061317.2746994,11.641473054885864,-4.634957175230617,1744061317.2747014,11.641473054885864,-22.219071277931977,1744061317.2747035,11.641473054885864,0.021416487838947597,1744061317.2747056,11.641473054885864,-56568542383.615204,1744061317.2747066,11.641473054885864,0.065,1744061317.2747078,11.641473054885864,3.141592653195863,1744061317.274709,11.641473054885864,22.284065372540528,1744061317.2747097,11.641473054885864,3.208905426799857e-20,1744061317.274711,11.641473054885864,4.525459766261869e-08,1744061317.274712,11.641473054885864,0.0,1744061317.2747128,11.641473054885864,-22627416997.969524,1744061317.2747138,11.641473054885864,0.0,1744061317.274715,11.641473054885864,28284271247.461903
+1744061317.2954965,11.661443710327148,-4.634957175230617,1744061317.2954996,11.661443710327148,-22.219071277931977,1744061317.2955043,11.661443710327148,0.021416487838947597,1744061317.295507,11.661443710327148,-56568542383.615204,1744061317.295509,11.661443710327148,0.065,1744061317.2955108,11.661443710327148,3.141592653195863,1744061317.2955134,11.661443710327148,22.284065372540528,1744061317.2955153,11.661443710327148,3.208905426799857e-20,1744061317.2955167,11.661443710327148,4.525459766261869e-08,1744061317.2955186,11.661443710327148,0.0,1744061317.29552,11.661443710327148,-22627416997.969524,1744061317.2955213,11.661443710327148,0.0,1744061317.295523,11.661443710327148,28284271247.461903
+1744061317.3150096,11.681471586227417,-4.634957175230617,1744061317.3150117,11.681471586227417,-22.219071277931977,1744061317.3150144,11.681471586227417,0.021416487838947597,1744061317.3150165,11.681471586227417,-56568542383.615204,1744061317.3150177,11.681471586227417,0.065,1744061317.315019,11.681471586227417,3.141592653195863,1744061317.31502,11.681471586227417,22.284065372540528,1744061317.3150208,11.681471586227417,3.208905426799857e-20,1744061317.3150218,11.681471586227417,4.525459766261869e-08,1744061317.3150232,11.681471586227417,0.0,1744061317.3150241,11.681471586227417,-22627416997.969524,1744061317.3150249,11.681471586227417,0.0,1744061317.3150258,11.681471586227417,28284271247.461903
+1744061317.3353286,11.701451539993286,-5.091162672069342,1744061317.3353305,11.701451539993286,-24.541811105503577,1744061317.3353326,11.701451539993286,0.021416487838947597,1744061317.3353345,11.701451539993286,-56568542383.615204,1744061317.335336,11.701451539993286,0.065,1744061317.3353372,11.701451539993286,3.141592653154802,1744061317.3353384,11.701451539993286,24.6068224687391,1744061317.3353393,11.701451539993286,3.5433824500807e-20,1744061317.3353403,11.701451539993286,7.057554432475679e-09,1744061317.335342,11.701451539993286,0.0,1744061317.3353426,11.701451539993286,-22627416997.969524,1744061317.3353438,11.701451539993286,0.0,1744061317.3353446,11.701451539993286,28284271247.461903
+1744061317.3552272,11.7215256690979,-5.091162672069342,1744061317.3552294,11.7215256690979,-24.541811105503577,1744061317.3552318,11.7215256690979,0.021416487838947597,1744061317.355234,11.7215256690979,-56568542383.615204,1744061317.3552349,11.7215256690979,0.065,1744061317.355236,11.7215256690979,3.141592653154802,1744061317.355237,11.7215256690979,24.6068224687391,1744061317.3552382,11.7215256690979,3.5433824500807e-20,1744061317.3552392,11.7215256690979,7.057554432475679e-09,1744061317.35524,11.7215256690979,0.0,1744061317.3552413,11.7215256690979,-22627416997.969524,1744061317.3552423,11.7215256690979,0.0,1744061317.3552432,11.7215256690979,28284271247.461903
+1744061317.3760836,11.741462707519531,-5.091162672069342,1744061317.3760855,11.741462707519531,-24.541811105503577,1744061317.3760881,11.741462707519531,0.021416487838947597,1744061317.37609,11.741462707519531,-56568542383.615204,1744061317.3760912,11.741462707519531,0.065,1744061317.3760924,11.741462707519531,3.141592653154802,1744061317.3760934,11.741462707519531,24.6068224687391,1744061317.3760946,11.741462707519531,3.5433824500807e-20,1744061317.3760955,11.741462707519531,7.057554432475679e-09,1744061317.3760965,11.741462707519531,0.0,1744061317.3760974,11.741462707519531,-22627416997.969524,1744061317.3760986,11.741462707519531,0.0,1744061317.3760993,11.741462707519531,28284271247.461903
+1744061317.3946962,11.761441707611084,-5.091162672069342,1744061317.3946981,11.761441707611084,-24.541811105503577,1744061317.3947005,11.761441707611084,0.021416487838947597,1744061317.394703,11.761441707611084,-56568542383.615204,1744061317.3947039,11.761441707611084,0.065,1744061317.394705,11.761441707611084,3.141592653154802,1744061317.3947067,11.761441707611084,24.6068224687391,1744061317.3947074,11.761441707611084,3.5433824500807e-20,1744061317.3947084,11.761441707611084,7.057554432475679e-09,1744061317.3947098,11.761441707611084,0.0,1744061317.3947105,11.761441707611084,-22627416997.969524,1744061317.3947115,11.761441707611084,0.0,1744061317.3947127,11.761441707611084,28284271247.461903
+1744061317.4147203,11.78144907951355,-5.091162672069342,1744061317.414722,11.78144907951355,-24.541811105503577,1744061317.4147246,11.78144907951355,0.021416487838947597,1744061317.4147267,11.78144907951355,-56568542383.615204,1744061317.4147277,11.78144907951355,0.065,1744061317.4147289,11.78144907951355,3.141592653154802,1744061317.41473,11.78144907951355,24.6068224687391,1744061317.414731,11.78144907951355,3.5433824500807e-20,1744061317.4147317,11.78144907951355,7.057554432475679e-09,1744061317.4147332,11.78144907951355,0.0,1744061317.4147341,11.78144907951355,-22627416997.969524,1744061317.4147348,11.78144907951355,0.0,1744061317.4147358,11.78144907951355,28284271247.461903
+1744061317.434849,11.801443099975586,-5.091162672069342,1744061317.434851,11.801443099975586,-24.541811105503577,1744061317.434853,11.801443099975586,0.021416487838947597,1744061317.4348552,11.801443099975586,-56568542383.615204,1744061317.4348562,11.801443099975586,0.065,1744061317.4348574,11.801443099975586,3.141592653154802,1744061317.4348586,11.801443099975586,24.6068224687391,1744061317.4348593,11.801443099975586,3.5433824500807e-20,1744061317.4348602,11.801443099975586,7.057554432475679e-09,1744061317.4348614,11.801443099975586,0.0,1744061317.4348624,11.801443099975586,-22627416997.969524,1744061317.4348633,11.801443099975586,0.0,1744061317.434864,11.801443099975586,28284271247.461903
+1744061317.4550495,11.821500539779663,-5.091162672069342,1744061317.4550526,11.821500539779663,-24.541811105503577,1744061317.4550564,11.821500539779663,0.021416487838947597,1744061317.45506,11.821500539779663,-56568542383.615204,1744061317.4550617,11.821500539779663,0.065,1744061317.455064,11.821500539779663,3.141592653154802,1744061317.4550664,11.821500539779663,24.6068224687391,1744061317.4550683,11.821500539779663,3.5433824500807e-20,1744061317.4550703,11.821500539779663,7.057554432475679e-09,1744061317.4550724,11.821500539779663,0.0,1744061317.4550745,11.821500539779663,-22627416997.969524,1744061317.4550765,11.821500539779663,0.0,1744061317.4550786,11.821500539779663,28284271247.461903
+1744061317.4751115,11.84144401550293,-5.091162672069342,1744061317.4751139,11.84144401550293,-24.541811105503577,1744061317.4751177,11.84144401550293,0.021416487838947597,1744061317.4751205,11.84144401550293,-56568542383.615204,1744061317.475122,11.84144401550293,0.065,1744061317.475124,11.84144401550293,3.141592653154802,1744061317.475126,11.84144401550293,24.6068224687391,1744061317.4751272,11.84144401550293,3.5433824500807e-20,1744061317.475129,11.84144401550293,7.057554432475679e-09,1744061317.4751303,11.84144401550293,0.0,1744061317.4751322,11.84144401550293,-22627416997.969524,1744061317.4751337,11.84144401550293,0.0,1744061317.4751356,11.84144401550293,28284271247.461903
+1744061317.4946668,11.86144733428955,-5.091162672069342,1744061317.4946687,11.86144733428955,-24.541811105503577,1744061317.494671,11.86144733428955,0.021416487838947597,1744061317.4946733,11.86144733428955,-56568542383.615204,1744061317.4946744,11.86144733428955,0.065,1744061317.4946754,11.86144733428955,3.141592653154802,1744061317.4946766,11.86144733428955,24.6068224687391,1744061317.4946775,11.86144733428955,3.5433824500807e-20,1744061317.4946785,11.86144733428955,7.057554432475679e-09,1744061317.4946795,11.86144733428955,0.0,1744061317.4946806,11.86144733428955,-22627416997.969524,1744061317.4946816,11.86144733428955,0.0,1744061317.4946823,11.86144733428955,28284271247.461903
+1744061317.5148242,11.881483554840088,-5.091162672069342,1744061317.5148263,11.881483554840088,-24.541811105503577,1744061317.5148284,11.881483554840088,0.021416487838947597,1744061317.5148306,11.881483554840088,-56568542383.615204,1744061317.5148315,11.881483554840088,0.065,1744061317.514833,11.881483554840088,3.141592653154802,1744061317.5148342,11.881483554840088,24.6068224687391,1744061317.514835,11.881483554840088,3.5433824500807e-20,1744061317.514836,11.881483554840088,7.057554432475679e-09,1744061317.514837,11.881483554840088,0.0,1744061317.5148377,11.881483554840088,-22627416997.969524,1744061317.5148387,11.881483554840088,0.0,1744061317.51484,11.881483554840088,28284271247.461903
+1744061317.5357974,11.901479482650757,-5.091162672069342,1744061317.5358,11.901479482650757,-24.541811105503577,1744061317.5358028,11.901479482650757,0.021416487838947597,1744061317.5358064,11.901479482650757,-56568542383.615204,1744061317.5358083,11.901479482650757,0.065,1744061317.5358105,11.901479482650757,3.141592653154802,1744061317.5358124,11.901479482650757,24.6068224687391,1744061317.535814,11.901479482650757,3.5433824500807e-20,1744061317.5358162,11.901479482650757,7.057554432475679e-09,1744061317.5358183,11.901479482650757,0.0,1744061317.53582,11.901479482650757,-22627416997.969524,1744061317.535822,11.901479482650757,0.0,1744061317.5358238,11.901479482650757,28284271247.461903
+1744061317.555529,11.921512365341187,-5.091162672069342,1744061317.5555549,11.921512365341187,-24.541811105503577,1744061317.5555587,11.921512365341187,0.021416487838947597,1744061317.5555618,11.921512365341187,-56568542383.615204,1744061317.555563,11.921512365341187,0.065,1744061317.5555649,11.921512365341187,3.141592653154802,1744061317.5555663,11.921512365341187,24.6068224687391,1744061317.555567,11.921512365341187,3.5433824500807e-20,1744061317.5555687,11.921512365341187,7.057554432475679e-09,1744061317.5555713,11.921512365341187,0.0,1744061317.555573,11.921512365341187,-22627416997.969524,1744061317.5555742,11.921512365341187,0.0,1744061317.5555756,11.921512365341187,28284271247.461903
+1744061317.5752451,11.941451072692871,-5.091162672069342,1744061317.5752482,11.941451072692871,-24.541811105503577,1744061317.575252,11.941451072692871,0.021416487838947597,1744061317.5752556,11.941451072692871,-56568542383.615204,1744061317.5752573,11.941451072692871,0.065,1744061317.5752597,11.941451072692871,3.141592653154802,1744061317.5752614,11.941451072692871,24.6068224687391,1744061317.5752635,11.941451072692871,3.5433824500807e-20,1744061317.5752652,11.941451072692871,7.057554432475679e-09,1744061317.5752676,11.941451072692871,0.0,1744061317.5752695,11.941451072692871,-22627416997.969524,1744061317.5752714,11.941451072692871,0.0,1744061317.5752733,11.941451072692871,28284271247.461903
+1744061317.5947387,11.961472034454346,-5.091162672069342,1744061317.5947413,11.961472034454346,-24.541811105503577,1744061317.594744,11.961472034454346,0.021416487838947597,1744061317.594748,11.961472034454346,-56568542383.615204,1744061317.5947497,11.961472034454346,0.065,1744061317.5947506,11.961472034454346,3.141592653154802,1744061317.594752,11.961472034454346,24.6068224687391,1744061317.5947528,11.961472034454346,3.5433824500807e-20,1744061317.5947537,11.961472034454346,7.057554432475679e-09,1744061317.594755,11.961472034454346,0.0,1744061317.594756,11.961472034454346,-22627416997.969524,1744061317.5947566,11.961472034454346,0.0,1744061317.5947576,11.961472034454346,28284271247.461903
+1744061317.6148193,11.981475114822388,-5.091162672069342,1744061317.6148217,11.981475114822388,-24.541811105503577,1744061317.6148238,11.981475114822388,0.021416487838947597,1744061317.6148262,11.981475114822388,-56568542383.615204,1744061317.6148272,11.981475114822388,0.065,1744061317.6148286,11.981475114822388,3.141592653154802,1744061317.6148298,11.981475114822388,24.6068224687391,1744061317.6148305,11.981475114822388,3.5433824500807e-20,1744061317.6148317,11.981475114822388,7.057554432475679e-09,1744061317.6148326,11.981475114822388,0.0,1744061317.6148336,11.981475114822388,-22627416997.969524,1744061317.6148348,11.981475114822388,0.0,1744061317.6148355,11.981475114822388,28284271247.461903
+1744061317.6350038,12.001474857330322,-5.091162672069342,1744061317.6350055,12.001474857330322,-24.541811105503577,1744061317.6350079,12.001474857330322,0.021416487838947597,1744061317.63501,12.001474857330322,-56568542383.615204,1744061317.635011,12.001474857330322,0.065,1744061317.6350265,12.001474857330322,3.141592653154802,1744061317.6350274,12.001474857330322,24.6068224687391,1744061317.6350284,12.001474857330322,3.5433824500807e-20,1744061317.6350293,12.001474857330322,7.057554432475679e-09,1744061317.6350305,12.001474857330322,0.0,1744061317.6350312,12.001474857330322,-22627416997.969524,1744061317.6350324,12.001474857330322,0.0,1744061317.6350334,12.001474857330322,28284271247.461903
+1744061317.6550183,12.021513223648071,-5.091162672069342,1744061317.65502,12.021513223648071,-24.541811105503577,1744061317.6550226,12.021513223648071,0.021416487838947597,1744061317.6550245,12.021513223648071,-56568542383.615204,1744061317.6550257,12.021513223648071,0.065,1744061317.655027,12.021513223648071,3.141592653154802,1744061317.6550279,12.021513223648071,24.6068224687391,1744061317.655029,12.021513223648071,3.5433824500807e-20,1744061317.65503,12.021513223648071,7.057554432475679e-09,1744061317.6550312,12.021513223648071,0.0,1744061317.6550322,12.021513223648071,-22627416997.969524,1744061317.655033,12.021513223648071,0.0,1744061317.655034,12.021513223648071,28284271247.461903
+1744061317.6747193,12.041437864303589,-5.091162672069342,1744061317.6747217,12.041437864303589,-24.541811105503577,1744061317.6747253,12.041437864303589,0.021416487838947597,1744061317.6747284,12.041437864303589,-56568542383.615204,1744061317.67473,12.041437864303589,0.065,1744061317.6747322,12.041437864303589,3.141592653154802,1744061317.674734,12.041437864303589,24.6068224687391,1744061317.6747358,12.041437864303589,3.5433824500807e-20,1744061317.6747375,12.041437864303589,7.057554432475679e-09,1744061317.674739,12.041437864303589,0.0,1744061317.67474,12.041437864303589,-22627416997.969524,1744061317.6747422,12.041437864303589,0.0,1744061317.674744,12.041437864303589,28284271247.461903
+1744061317.694825,12.06148386001587,-5.091162672069342,1744061317.6948292,12.06148386001587,-24.541811105503577,1744061317.6948318,12.06148386001587,0.021416487838947597,1744061317.6948354,12.06148386001587,-56568542383.615204,1744061317.694837,12.06148386001587,0.065,1744061317.6948392,12.06148386001587,3.141592653154802,1744061317.694841,12.06148386001587,24.6068224687391,1744061317.694842,12.06148386001587,3.5433824500807e-20,1744061317.694844,12.06148386001587,7.057554432475679e-09,1744061317.6948452,12.06148386001587,0.0,1744061317.6948466,12.06148386001587,-22627416997.969524,1744061317.694848,12.06148386001587,0.0,1744061317.6948493,12.06148386001587,28284271247.461903
+1744061317.7146726,12.081468105316162,-5.091162672069342,1744061317.7146745,12.081468105316162,-24.541811105503577,1744061317.714677,12.081468105316162,0.021416487838947597,1744061317.714679,12.081468105316162,-56568542383.615204,1744061317.7146804,12.081468105316162,0.065,1744061317.7146816,12.081468105316162,3.141592653154802,1744061317.7146826,12.081468105316162,24.6068224687391,1744061317.7146833,12.081468105316162,3.5433824500807e-20,1744061317.7146845,12.081468105316162,7.057554432475679e-09,1744061317.7146857,12.081468105316162,0.0,1744061317.7146866,12.081468105316162,-22627416997.969524,1744061317.7146878,12.081468105316162,0.0,1744061317.7146885,12.081468105316162,28284271247.461903
+1744061317.7352548,12.10145878791809,-5.091162672069342,1744061317.7352567,12.10145878791809,-24.541811105503577,1744061317.7352586,12.10145878791809,0.021416487838947597,1744061317.7352607,12.10145878791809,-56568542383.615204,1744061317.7352617,12.10145878791809,0.065,1744061317.7352629,12.10145878791809,3.141592653154802,1744061317.735264,12.10145878791809,24.6068224687391,1744061317.735265,12.10145878791809,3.5433824500807e-20,1744061317.7352657,12.10145878791809,7.057554432475679e-09,1744061317.7352672,12.10145878791809,0.0,1744061317.7352679,12.10145878791809,-22627416997.969524,1744061317.7352688,12.10145878791809,0.0,1744061317.7352695,12.10145878791809,28284271247.461903
+1744061317.7547197,12.121450185775757,-5.091162672069342,1744061317.7547219,12.121450185775757,-24.541811105503577,1744061317.7547243,12.121450185775757,0.021416487838947597,1744061317.7547266,12.121450185775757,-56568542383.615204,1744061317.7547276,12.121450185775757,0.065,1744061317.7547293,12.121450185775757,3.141592653154802,1744061317.7547302,12.121450185775757,24.6068224687391,1744061317.7547312,12.121450185775757,3.5433824500807e-20,1744061317.7547324,12.121450185775757,7.057554432475679e-09,1744061317.7547333,12.121450185775757,0.0,1744061317.7547343,12.121450185775757,-22627416997.969524,1744061317.7547355,12.121450185775757,0.0,1744061317.7547362,12.121450185775757,28284271247.461903
+1744061317.7746959,12.141461372375488,-5.091162672069342,1744061317.7746975,12.141461372375488,-24.541811105503577,1744061317.7747,12.141461372375488,0.021416487838947597,1744061317.774702,12.141461372375488,-56568542383.615204,1744061317.774703,12.141461372375488,0.065,1744061317.7747045,12.141461372375488,3.141592653154802,1744061317.7747054,12.141461372375488,24.6068224687391,1744061317.7747061,12.141461372375488,3.5433824500807e-20,1744061317.7747073,12.141461372375488,7.057554432475679e-09,1744061317.7747085,12.141461372375488,0.0,1744061317.7747092,12.141461372375488,-22627416997.969524,1744061317.7747104,12.141461372375488,0.0,1744061317.7747114,12.141461372375488,28284271247.461903
+1744061317.7962909,12.16156554222107,-5.091162672069342,1744061317.7962928,12.16156554222107,-24.541811105503577,1744061317.7962954,12.16156554222107,0.021416487838947597,1744061317.7962976,12.16156554222107,-56568542383.615204,1744061317.7962987,12.16156554222107,0.065,1744061317.7963002,12.16156554222107,3.141592653154802,1744061317.7963014,12.16156554222107,24.6068224687391,1744061317.7963023,12.16156554222107,3.5433824500807e-20,1744061317.796303,12.16156554222107,7.057554432475679e-09,1744061317.7963045,12.16156554222107,0.0,1744061317.7963052,12.16156554222107,-22627416997.969524,1744061317.7963064,12.16156554222107,0.0,1744061317.7963078,12.16156554222107,28284271247.461903
+1744061317.8146849,12.18147587776184,-5.091162672069342,1744061317.8146868,12.18147587776184,-24.541811105503577,1744061317.814689,12.18147587776184,0.021416487838947597,1744061317.814691,12.18147587776184,-56568542383.615204,1744061317.814692,12.18147587776184,0.065,1744061317.8146935,12.18147587776184,3.141592653154802,1744061317.8146944,12.18147587776184,24.6068224687391,1744061317.8146954,12.18147587776184,3.5433824500807e-20,1744061317.814696,12.18147587776184,7.057554432475679e-09,1744061317.8146973,12.18147587776184,0.0,1744061317.8146982,12.18147587776184,-22627416997.969524,1744061317.8146992,12.18147587776184,0.0,1744061317.8147001,12.18147587776184,28284271247.461903
+1744061317.835004,12.201493501663208,-5.446192194340855,1744061317.8350058,12.201493501663208,-26.44826588337261,1744061317.835008,12.201493501663208,0.021416487838947597,1744061317.8350098,12.201493501663208,-56568542383.615204,1744061317.8350108,12.201493501663208,0.065,1744061317.8350122,12.201493501663208,3.1415926531211005,1744061317.8350132,12.201493501663208,26.5132664102027,1744061317.835014,12.201493501663208,3.81791037882916e-20,1744061317.8350148,12.201493501663208,1.5356341774830768e-09,1744061317.835016,12.201493501663208,0.0,1744061317.835017,12.201493501663208,-22627416997.969524,1744061317.8350177,12.201493501663208,0.0,1744061317.8350186,12.201493501663208,28284271247.461903
+1744061317.854835,12.221486330032349,-5.446192194340855,1744061317.8548367,12.221486330032349,-26.44826588337261,1744061317.8548393,12.221486330032349,0.021416487838947597,1744061317.8548412,12.221486330032349,-56568542383.615204,1744061317.8548424,12.221486330032349,0.065,1744061317.8548439,12.221486330032349,3.1415926531211005,1744061317.854845,12.221486330032349,26.5132664102027,1744061317.8548458,12.221486330032349,3.81791037882916e-20,1744061317.854847,12.221486330032349,1.5356341774830768e-09,1744061317.854848,12.221486330032349,0.0,1744061317.854849,12.221486330032349,-22627416997.969524,1744061317.85485,12.221486330032349,0.0,1744061317.8548508,12.221486330032349,28284271247.461903
+1744061317.8749654,12.241499900817871,-5.446192194340855,1744061317.8749676,12.241499900817871,-26.44826588337261,1744061317.8749704,12.241499900817871,0.021416487838947597,1744061317.8749726,12.241499900817871,-56568542383.615204,1744061317.874974,12.241499900817871,0.065,1744061317.8749752,12.241499900817871,3.1415926531211005,1744061317.8749764,12.241499900817871,26.5132664102027,1744061317.8749774,12.241499900817871,3.81791037882916e-20,1744061317.8749785,12.241499900817871,1.5356341774830768e-09,1744061317.8749797,12.241499900817871,0.0,1744061317.8749807,12.241499900817871,-22627416997.969524,1744061317.8749819,12.241499900817871,0.0,1744061317.8749826,12.241499900817871,28284271247.461903
+1744061317.8949518,12.261505365371704,-5.446192194340855,1744061317.8949542,12.261505365371704,-26.44826588337261,1744061317.8949568,12.261505365371704,0.021416487838947597,1744061317.8949587,12.261505365371704,-56568542383.615204,1744061317.89496,12.261505365371704,0.065,1744061317.894961,12.261505365371704,3.1415926531211005,1744061317.8949625,12.261505365371704,26.5132664102027,1744061317.8949633,12.261505365371704,3.81791037882916e-20,1744061317.8949642,12.261505365371704,1.5356341774830768e-09,1744061317.8949652,12.261505365371704,0.0,1744061317.8949664,12.261505365371704,-22627416997.969524,1744061317.8949673,12.261505365371704,0.0,1744061317.894968,12.261505365371704,28284271247.461903
+1744061317.914645,12.281483173370361,-5.446192194340855,1744061317.9146473,12.281483173370361,-26.44826588337261,1744061317.9146655,12.281483173370361,0.021416487838947597,1744061317.9146678,12.281483173370361,-56568542383.615204,1744061317.9146688,12.281483173370361,0.065,1744061317.91467,12.281483173370361,3.1415926531211005,1744061317.9146712,12.281483173370361,26.5132664102027,1744061317.914672,12.281483173370361,3.81791037882916e-20,1744061317.9146729,12.281483173370361,1.5356341774830768e-09,1744061317.9146907,12.281483173370361,0.0,1744061317.914692,12.281483173370361,-22627416997.969524,1744061317.9146929,12.281483173370361,0.0,1744061317.9146936,12.281483173370361,28284271247.461903
+1744061317.93495,12.301484823226929,-5.446192194340855,1744061317.934952,12.301484823226929,-26.44826588337261,1744061317.9349542,12.301484823226929,0.021416487838947597,1744061317.9349563,12.301484823226929,-56568542383.615204,1744061317.9349575,12.301484823226929,0.065,1744061317.934959,12.301484823226929,3.1415926531211005,1744061317.93496,12.301484823226929,26.5132664102027,1744061317.9349608,12.301484823226929,3.81791037882916e-20,1744061317.934962,12.301484823226929,1.5356341774830768e-09,1744061317.934963,12.301484823226929,0.0,1744061317.934964,12.301484823226929,-22627416997.969524,1744061317.9349647,12.301484823226929,0.0,1744061317.9349658,12.301484823226929,28284271247.461903
+1744061317.9559925,12.321514368057251,-5.446192194340855,1744061317.955997,12.321514368057251,-26.44826588337261,1744061317.9560013,12.321514368057251,0.021416487838947597,1744061317.956005,12.321514368057251,-56568542383.615204,1744061317.9560072,12.321514368057251,0.065,1744061317.9560096,12.321514368057251,3.1415926531211005,1744061317.956012,12.321514368057251,26.5132664102027,1744061317.9560132,12.321514368057251,3.81791037882916e-20,1744061317.9560149,12.321514368057251,1.5356341774830768e-09,1744061317.956021,12.321514368057251,0.0,1744061317.9560225,12.321514368057251,-22627416997.969524,1744061317.9560237,12.321514368057251,0.0,1744061317.956025,12.321514368057251,28284271247.461903
+1744061317.9756474,12.341452836990356,-5.446192194340855,1744061317.9756703,12.341452836990356,-26.44826588337261,1744061317.9756746,12.341452836990356,0.021416487838947597,1744061317.975679,12.341452836990356,-56568542383.615204,1744061317.9756808,12.341452836990356,0.065,1744061317.9756837,12.341452836990356,3.1415926531211005,1744061317.975686,12.341452836990356,26.5132664102027,1744061317.975688,12.341452836990356,3.81791037882916e-20,1744061317.9756901,12.341452836990356,1.5356341774830768e-09,1744061317.9756925,12.341452836990356,0.0,1744061317.9756947,12.341452836990356,-22627416997.969524,1744061317.9756966,12.341452836990356,0.0,1744061317.9756987,12.341452836990356,28284271247.461903
+1744061317.9956288,12.36159634590149,-5.446192194340855,1744061317.9956312,12.36159634590149,-26.44826588337261,1744061317.9956338,12.36159634590149,0.021416487838947597,1744061317.9956362,12.36159634590149,-56568542383.615204,1744061317.9956374,12.36159634590149,0.065,1744061317.995639,12.36159634590149,3.1415926531211005,1744061317.9956403,12.36159634590149,26.5132664102027,1744061317.9956412,12.36159634590149,3.81791037882916e-20,1744061317.9956427,12.36159634590149,1.5356341774830768e-09,1744061317.995644,12.36159634590149,0.0,1744061317.9956453,12.36159634590149,-22627416997.969524,1744061317.9956462,12.36159634590149,0.0,1744061317.9956477,12.36159634590149,28284271247.461903
+1744061318.0149143,12.381494045257568,-5.446192194340855,1744061318.014916,12.381494045257568,-26.44826588337261,1744061318.0149183,12.381494045257568,0.021416487838947597,1744061318.0149205,12.381494045257568,-56568542383.615204,1744061318.0149214,12.381494045257568,0.065,1744061318.0149229,12.381494045257568,3.1415926531211005,1744061318.0149238,12.381494045257568,26.5132664102027,1744061318.0149248,12.381494045257568,3.81791037882916e-20,1744061318.0149255,12.381494045257568,1.5356341774830768e-09,1744061318.014927,12.381494045257568,0.0,1744061318.0149279,12.381494045257568,-22627416997.969524,1744061318.0149286,12.381494045257568,0.0,1744061318.0149298,12.381494045257568,28284271247.461903
+1744061318.0349193,12.401475667953491,-5.446192194340855,1744061318.034921,12.401475667953491,-26.44826588337261,1744061318.0349228,12.401475667953491,0.021416487838947597,1744061318.0349247,12.401475667953491,-56568542383.615204,1744061318.034926,12.401475667953491,0.065,1744061318.0349271,12.401475667953491,3.1415926531211005,1744061318.034928,12.401475667953491,26.5132664102027,1744061318.034929,12.401475667953491,3.81791037882916e-20,1744061318.0349302,12.401475667953491,1.5356341774830768e-09,1744061318.0349314,12.401475667953491,0.0,1744061318.0349321,12.401475667953491,-22627416997.969524,1744061318.0349333,12.401475667953491,0.0,1744061318.0349343,12.401475667953491,28284271247.461903
+1744061318.0550437,12.421473026275635,-5.446192194340855,1744061318.0550456,12.421473026275635,-26.44826588337261,1744061318.0550482,12.421473026275635,0.021416487838947597,1744061318.0550506,12.421473026275635,-56568542383.615204,1744061318.0550518,12.421473026275635,0.065,1744061318.055053,12.421473026275635,3.1415926531211005,1744061318.0550542,12.421473026275635,26.5132664102027,1744061318.0550551,12.421473026275635,3.81791037882916e-20,1744061318.0550563,12.421473026275635,1.5356341774830768e-09,1744061318.0550578,12.421473026275635,0.0,1744061318.0550587,12.421473026275635,-22627416997.969524,1744061318.0550594,12.421473026275635,0.0,1744061318.0550604,12.421473026275635,28284271247.461903
+1744061318.0747457,12.441471338272095,-5.446192194340855,1744061318.0747473,12.441471338272095,-26.44826588337261,1744061318.0747497,12.441471338272095,0.021416487838947597,1744061318.074752,12.441471338272095,-56568542383.615204,1744061318.0747528,12.441471338272095,0.065,1744061318.074754,12.441471338272095,3.1415926531211005,1744061318.0747554,12.441471338272095,26.5132664102027,1744061318.0747561,12.441471338272095,3.81791037882916e-20,1744061318.074757,12.441471338272095,1.5356341774830768e-09,1744061318.074758,12.441471338272095,0.0,1744061318.0747592,12.441471338272095,-22627416997.969524,1744061318.07476,12.441471338272095,0.0,1744061318.074761,12.441471338272095,28284271247.461903
+1744061318.0951579,12.46148157119751,-5.446192194340855,1744061318.0951598,12.46148157119751,-26.44826588337261,1744061318.0951629,12.46148157119751,0.021416487838947597,1744061318.0951653,12.46148157119751,-56568542383.615204,1744061318.0951662,12.46148157119751,0.065,1744061318.0951676,12.46148157119751,3.1415926531211005,1744061318.095169,12.46148157119751,26.5132664102027,1744061318.09517,12.46148157119751,3.81791037882916e-20,1744061318.0951717,12.46148157119751,1.5356341774830768e-09,1744061318.095173,12.46148157119751,0.0,1744061318.0951738,12.46148157119751,-22627416997.969524,1744061318.0951753,12.46148157119751,0.0,1744061318.0951762,12.46148157119751,28284271247.461903
+1744061318.1148643,12.481451988220215,-5.446192194340855,1744061318.114866,12.481451988220215,-26.44826588337261,1744061318.1148684,12.481451988220215,0.021416487838947597,1744061318.1148705,12.481451988220215,-56568542383.615204,1744061318.1148715,12.481451988220215,0.065,1744061318.114873,12.481451988220215,3.1415926531211005,1744061318.114874,12.481451988220215,26.5132664102027,1744061318.1148748,12.481451988220215,3.81791037882916e-20,1744061318.1148756,12.481451988220215,1.5356341774830768e-09,1744061318.114877,12.481451988220215,0.0,1744061318.114878,12.481451988220215,-22627416997.969524,1744061318.1148787,12.481451988220215,0.0,1744061318.1148798,12.481451988220215,28284271247.461903
+1744061318.1351879,12.50153112411499,-5.446192194340855,1744061318.1351898,12.50153112411499,-26.44826588337261,1744061318.1351924,12.50153112411499,0.021416487838947597,1744061318.1351943,12.50153112411499,-56568542383.615204,1744061318.1351955,12.50153112411499,0.065,1744061318.1351967,12.50153112411499,3.1415926531211005,1744061318.1351976,12.50153112411499,26.5132664102027,1744061318.1351988,12.50153112411499,3.81791037882916e-20,1744061318.1351995,12.50153112411499,1.5356341774830768e-09,1744061318.1352007,12.50153112411499,0.0,1744061318.1352015,12.50153112411499,-22627416997.969524,1744061318.1352026,12.50153112411499,0.0,1744061318.1352034,12.50153112411499,28284271247.461903
+1744061318.1552918,12.521534442901611,-5.446192194340855,1744061318.1552944,12.521534442901611,-26.44826588337261,1744061318.1552975,12.521534442901611,0.021416487838947597,1744061318.1553,12.521534442901611,-56568542383.615204,1744061318.155301,12.521534442901611,0.065,1744061318.1553023,12.521534442901611,3.1415926531211005,1744061318.155304,12.521534442901611,26.5132664102027,1744061318.1553047,12.521534442901611,3.81791037882916e-20,1744061318.1553063,12.521534442901611,1.5356341774830768e-09,1744061318.1553075,12.521534442901611,0.0,1744061318.1553085,12.521534442901611,-22627416997.969524,1744061318.15531,12.521534442901611,0.0,1744061318.1553109,12.521534442901611,28284271247.461903
+1744061318.17498,12.541462898254395,-5.446192194340855,1744061318.1749816,12.541462898254395,-26.44826588337261,1744061318.1749842,12.541462898254395,0.021416487838947597,1744061318.1749866,12.541462898254395,-56568542383.615204,1744061318.1749876,12.541462898254395,0.065,1744061318.1749887,12.541462898254395,3.1415926531211005,1744061318.1749902,12.541462898254395,26.5132664102027,1744061318.1749911,12.541462898254395,3.81791037882916e-20,1744061318.174992,12.541462898254395,1.5356341774830768e-09,1744061318.1749935,12.541462898254395,0.0,1744061318.1749942,12.541462898254395,-22627416997.969524,1744061318.1749954,12.541462898254395,0.0,1744061318.1749961,12.541462898254395,28284271247.461903
+1744061318.1947057,12.561446189880371,-5.446192194340855,1744061318.1947074,12.561446189880371,-26.44826588337261,1744061318.1947103,12.561446189880371,0.021416487838947597,1744061318.1947124,12.561446189880371,-56568542383.615204,1744061318.1947134,12.561446189880371,0.065,1744061318.1947145,12.561446189880371,3.1415926531211005,1744061318.1947157,12.561446189880371,26.5132664102027,1744061318.1947165,12.561446189880371,3.81791037882916e-20,1744061318.1947174,12.561446189880371,1.5356341774830768e-09,1744061318.1947184,12.561446189880371,0.0,1744061318.1947193,12.561446189880371,-22627416997.969524,1744061318.1947203,12.561446189880371,0.0,1744061318.1947212,12.561446189880371,28284271247.461903
+1744061318.2146337,12.58143949508667,-5.446192194340855,1744061318.2146356,12.58143949508667,-26.44826588337261,1744061318.2146375,12.58143949508667,0.021416487838947597,1744061318.21464,12.58143949508667,-56568542383.615204,1744061318.2146409,12.58143949508667,0.065,1744061318.2146423,12.58143949508667,3.1415926531211005,1744061318.2146432,12.58143949508667,26.5132664102027,1744061318.2146442,12.58143949508667,3.81791037882916e-20,1744061318.214645,12.58143949508667,1.5356341774830768e-09,1744061318.2146463,12.58143949508667,0.0,1744061318.214647,12.58143949508667,-22627416997.969524,1744061318.214648,12.58143949508667,0.0,1744061318.2146492,12.58143949508667,28284271247.461903
+1744061318.2350488,12.601446628570557,-5.446192194340855,1744061318.2350504,12.601446628570557,-26.44826588337261,1744061318.2350528,12.601446628570557,0.021416487838947597,1744061318.2350547,12.601446628570557,-56568542383.615204,1744061318.235056,12.601446628570557,0.065,1744061318.235057,12.601446628570557,3.1415926531211005,1744061318.235058,12.601446628570557,26.5132664102027,1744061318.235059,12.601446628570557,3.81791037882916e-20,1744061318.2350602,12.601446628570557,1.5356341774830768e-09,1744061318.2350612,12.601446628570557,0.0,1744061318.2350621,12.601446628570557,-22627416997.969524,1744061318.235063,12.601446628570557,0.0,1744061318.235064,12.601446628570557,28284271247.461903
+1744061318.255107,12.621456146240234,-5.446192194340855,1744061318.255109,12.621456146240234,-26.44826588337261,1744061318.255112,12.621456146240234,0.021416487838947597,1744061318.2551143,12.621456146240234,-56568542383.615204,1744061318.2551153,12.621456146240234,0.065,1744061318.2551167,12.621456146240234,3.1415926531211005,1744061318.2551181,12.621456146240234,26.5132664102027,1744061318.2551188,12.621456146240234,3.81791037882916e-20,1744061318.2551203,12.621456146240234,1.5356341774830768e-09,1744061318.2551224,12.621456146240234,0.0,1744061318.2551243,12.621456146240234,-22627416997.969524,1744061318.2551253,12.621456146240234,0.0,1744061318.2551262,12.621456146240234,28284271247.461903
+1744061318.2747586,12.641437292098999,-5.446192194340855,1744061318.2747607,12.641437292098999,-26.44826588337261,1744061318.2747633,12.641437292098999,0.021416487838947597,1744061318.2747653,12.641437292098999,-56568542383.615204,1744061318.2747667,12.641437292098999,0.065,1744061318.2747679,12.641437292098999,3.1415926531211005,1744061318.2747743,12.641437292098999,26.5132664102027,1744061318.2747753,12.641437292098999,3.81791037882916e-20,1744061318.274776,12.641437292098999,1.5356341774830768e-09,1744061318.2747774,12.641437292098999,0.0,1744061318.2747784,12.641437292098999,-22627416997.969524,1744061318.274779,12.641437292098999,0.0,1744061318.2747803,12.641437292098999,28284271247.461903
+1744061318.295192,12.661473274230957,-5.446192194340855,1744061318.295194,12.661473274230957,-26.44826588337261,1744061318.295196,12.661473274230957,0.021416487838947597,1744061318.2951982,12.661473274230957,-56568542383.615204,1744061318.2951992,12.661473274230957,0.065,1744061318.2952006,12.661473274230957,3.1415926531211005,1744061318.2952015,12.661473274230957,26.5132664102027,1744061318.2952023,12.661473274230957,3.81791037882916e-20,1744061318.2952032,12.661473274230957,1.5356341774830768e-09,1744061318.2952044,12.661473274230957,0.0,1744061318.2952054,12.661473274230957,-22627416997.969524,1744061318.295206,12.661473274230957,0.0,1744061318.2952073,12.661473274230957,28284271247.461903
+1744061318.314666,12.681437492370605,-5.446192194340855,1744061318.3146677,12.681437492370605,-26.44826588337261,1744061318.31467,12.681437492370605,0.021416487838947597,1744061318.3146722,12.681437492370605,-56568542383.615204,1744061318.3146732,12.681437492370605,0.065,1744061318.3146746,12.681437492370605,3.1415926531211005,1744061318.3146758,12.681437492370605,26.5132664102027,1744061318.3146765,12.681437492370605,3.81791037882916e-20,1744061318.3146775,12.681437492370605,1.5356341774830768e-09,1744061318.3146784,12.681437492370605,0.0,1744061318.3146796,12.681437492370605,-22627416997.969524,1744061318.3146803,12.681437492370605,0.0,1744061318.3146813,12.681437492370605,28284271247.461903
+1744061318.3353777,12.70145869255066,-5.747644876572703,1744061318.3353791,12.70145869255066,-27.946768295737943,1744061318.3353813,12.70145869255066,0.021416487838947597,1744061318.3353837,12.70145869255066,-56568542383.615204,1744061318.3353846,12.70145869255066,0.065,1744061318.3353858,12.70145869255066,3.1415926530946106,1744061318.335387,12.70145869255066,28.011762649528396,1744061318.3353877,12.70145869255066,4.0336938382257855e-20,1744061318.3353887,12.70145869255066,4.6308088116912266e-10,1744061318.3353896,12.70145869255066,0.0,1744061318.3353906,12.70145869255066,-22627416997.969524,1744061318.3353915,12.70145869255066,0.0,1744061318.3353925,12.70145869255066,28284271247.461903
+1744061318.3556972,12.721529722213745,-5.747644876572703,1744061318.355704,12.721529722213745,-27.946768295737943,1744061318.3557131,12.721529722213745,0.021416487838947597,1744061318.3557158,12.721529722213745,-56568542383.615204,1744061318.3557172,12.721529722213745,0.065,1744061318.3557193,12.721529722213745,3.1415926530946106,1744061318.3557212,12.721529722213745,28.011762649528396,1744061318.3557224,12.721529722213745,4.0336938382257855e-20,1744061318.3557248,12.721529722213745,4.6308088116912266e-10,1744061318.3557265,12.721529722213745,0.0,1744061318.3557281,12.721529722213745,-22627416997.969524,1744061318.3557296,12.721529722213745,0.0,1744061318.3557317,12.721529722213745,28284271247.461903
+1744061318.375361,12.74147891998291,-5.747644876572703,1744061318.3753629,12.74147891998291,-27.946768295737943,1744061318.3753653,12.74147891998291,0.021416487838947597,1744061318.3753855,12.74147891998291,-56568542383.615204,1744061318.375387,12.74147891998291,0.065,1744061318.3753881,12.74147891998291,3.1415926530946106,1744061318.3753893,12.74147891998291,28.011762649528396,1744061318.3753905,12.74147891998291,4.0336938382257855e-20,1744061318.3753912,12.74147891998291,4.6308088116912266e-10,1744061318.3753924,12.74147891998291,0.0,1744061318.3753936,12.74147891998291,-22627416997.969524,1744061318.3753943,12.74147891998291,0.0,1744061318.3754144,12.74147891998291,28284271247.461903
+1744061318.3946235,12.761439085006714,-5.747644876572703,1744061318.3946252,12.761439085006714,-27.946768295737943,1744061318.3946276,12.761439085006714,0.021416487838947597,1744061318.3946297,12.761439085006714,-56568542383.615204,1744061318.3946307,12.761439085006714,0.065,1744061318.3946319,12.761439085006714,3.1415926530946106,1744061318.394633,12.761439085006714,28.011762649528396,1744061318.394634,12.761439085006714,4.0336938382257855e-20,1744061318.3946347,12.761439085006714,4.6308088116912266e-10,1744061318.394636,12.761439085006714,0.0,1744061318.3946369,12.761439085006714,-22627416997.969524,1744061318.3946378,12.761439085006714,0.0,1744061318.3946385,12.761439085006714,28284271247.461903
+1744061318.414783,12.781490802764893,-5.747644876572703,1744061318.414785,12.781490802764893,-27.946768295737943,1744061318.4147878,12.781490802764893,0.021416487838947597,1744061318.41479,12.781490802764893,-56568542383.615204,1744061318.414791,12.781490802764893,0.065,1744061318.4147925,12.781490802764893,3.1415926530946106,1744061318.4147935,12.781490802764893,28.011762649528396,1744061318.4147944,12.781490802764893,4.0336938382257855e-20,1744061318.4147952,12.781490802764893,4.6308088116912266e-10,1744061318.4147966,12.781490802764893,0.0,1744061318.4147973,12.781490802764893,-22627416997.969524,1744061318.4147983,12.781490802764893,0.0,1744061318.4147992,12.781490802764893,28284271247.461903
+1744061318.435708,12.801488161087036,-5.747644876572703,1744061318.4357104,12.801488161087036,-27.946768295737943,1744061318.4357126,12.801488161087036,0.021416487838947597,1744061318.4357145,12.801488161087036,-56568542383.615204,1744061318.4357157,12.801488161087036,0.065,1744061318.4357169,12.801488161087036,3.1415926530946106,1744061318.4357178,12.801488161087036,28.011762649528396,1744061318.435719,12.801488161087036,4.0336938382257855e-20,1744061318.4357197,12.801488161087036,4.6308088116912266e-10,1744061318.435721,12.801488161087036,0.0,1744061318.4357216,12.801488161087036,-22627416997.969524,1744061318.4357228,12.801488161087036,0.0,1744061318.4357235,12.801488161087036,28284271247.461903
+1744061318.4561417,12.821531772613525,-5.747644876572703,1744061318.456144,12.821531772613525,-27.946768295737943,1744061318.456147,12.821531772613525,0.021416487838947597,1744061318.4561493,12.821531772613525,-56568542383.615204,1744061318.4561505,12.821531772613525,0.065,1744061318.456152,12.821531772613525,3.1415926530946106,1744061318.4561536,12.821531772613525,28.011762649528396,1744061318.4561553,12.821531772613525,4.0336938382257855e-20,1744061318.4561574,12.821531772613525,4.6308088116912266e-10,1744061318.4561596,12.821531772613525,0.0,1744061318.4561613,12.821531772613525,-22627416997.969524,1744061318.4561632,12.821531772613525,0.0,1744061318.4561653,12.821531772613525,28284271247.461903
+1744061318.474836,12.841535329818726,-5.747644876572703,1744061318.4748383,12.841535329818726,-27.946768295737943,1744061318.4748409,12.841535329818726,0.021416487838947597,1744061318.4748428,12.841535329818726,-56568542383.615204,1744061318.474844,12.841535329818726,0.065,1744061318.4748452,12.841535329818726,3.1415926530946106,1744061318.4748461,12.841535329818726,28.011762649528396,1744061318.474847,12.841535329818726,4.0336938382257855e-20,1744061318.474848,12.841535329818726,4.6308088116912266e-10,1744061318.4748492,12.841535329818726,0.0,1744061318.47485,12.841535329818726,-22627416997.969524,1744061318.4748514,12.841535329818726,0.0,1744061318.4748526,12.841535329818726,28284271247.461903
+1744061318.4951816,12.861478090286255,-5.747644876572703,1744061318.4951842,12.861478090286255,-27.946768295737943,1744061318.4952054,12.861478090286255,0.021416487838947597,1744061318.4952078,12.861478090286255,-56568542383.615204,1744061318.495209,12.861478090286255,0.065,1744061318.4952106,12.861478090286255,3.1415926530946106,1744061318.495212,12.861478090286255,28.011762649528396,1744061318.495213,12.861478090286255,4.0336938382257855e-20,1744061318.495214,12.861478090286255,4.6308088116912266e-10,1744061318.4952154,12.861478090286255,0.0,1744061318.4952164,12.861478090286255,-22627416997.969524,1744061318.4952176,12.861478090286255,0.0,1744061318.4952188,12.861478090286255,28284271247.461903
+1744061318.51481,12.881446838378906,-5.747644876572703,1744061318.514812,12.881446838378906,-27.946768295737943,1744061318.5148146,12.881446838378906,0.021416487838947597,1744061318.5148168,12.881446838378906,-56568542383.615204,1744061318.514818,12.881446838378906,0.065,1744061318.5148196,12.881446838378906,3.1415926530946106,1744061318.5148213,12.881446838378906,28.011762649528396,1744061318.514823,12.881446838378906,4.0336938382257855e-20,1744061318.5148244,12.881446838378906,4.6308088116912266e-10,1744061318.5148263,12.881446838378906,0.0,1744061318.514828,12.881446838378906,-22627416997.969524,1744061318.5148296,12.881446838378906,0.0,1744061318.5148313,12.881446838378906,28284271247.461903
+1744061318.5355144,12.901448965072632,-5.747644876572703,1744061318.5355165,12.901448965072632,-27.946768295737943,1744061318.5355186,12.901448965072632,0.021416487838947597,1744061318.5355208,12.901448965072632,-56568542383.615204,1744061318.5355217,12.901448965072632,0.065,1744061318.5355232,12.901448965072632,3.1415926530946106,1744061318.5355241,12.901448965072632,28.011762649528396,1744061318.5355248,12.901448965072632,4.0336938382257855e-20,1744061318.5355258,12.901448965072632,4.6308088116912266e-10,1744061318.535527,12.901448965072632,0.0,1744061318.5355277,12.901448965072632,-22627416997.969524,1744061318.5355287,12.901448965072632,0.0,1744061318.5355296,12.901448965072632,28284271247.461903
+1744061318.5547245,12.921451807022095,-5.747644876572703,1744061318.5547261,12.921451807022095,-27.946768295737943,1744061318.5547287,12.921451807022095,0.021416487838947597,1744061318.5547307,12.921451807022095,-56568542383.615204,1744061318.554732,12.921451807022095,0.065,1744061318.5547333,12.921451807022095,3.1415926530946106,1744061318.5547347,12.921451807022095,28.011762649528396,1744061318.5547354,12.921451807022095,4.0336938382257855e-20,1744061318.5547364,12.921451807022095,4.6308088116912266e-10,1744061318.5547376,12.921451807022095,0.0,1744061318.5547385,12.921451807022095,-22627416997.969524,1744061318.5547397,12.921451807022095,0.0,1744061318.5547407,12.921451807022095,28284271247.461903
+1744061318.5752742,12.941466093063354,-5.747644876572703,1744061318.5752766,12.941466093063354,-27.946768295737943,1744061318.57528,12.941466093063354,0.021416487838947597,1744061318.575282,12.941466093063354,-56568542383.615204,1744061318.575284,12.941466093063354,0.065,1744061318.5752854,12.941466093063354,3.1415926530946106,1744061318.5752869,12.941466093063354,28.011762649528396,1744061318.575288,12.941466093063354,4.0336938382257855e-20,1744061318.57529,12.941466093063354,4.6308088116912266e-10,1744061318.5753129,12.941466093063354,0.0,1744061318.5753143,12.941466093063354,-22627416997.969524,1744061318.5753155,12.941466093063354,0.0,1744061318.5753324,12.941466093063354,28284271247.461903
+1744061318.5948122,12.961477994918823,-5.747644876572703,1744061318.594814,12.961477994918823,-27.946768295737943,1744061318.5948164,12.961477994918823,0.021416487838947597,1744061318.5948186,12.961477994918823,-56568542383.615204,1744061318.5948198,12.961477994918823,0.065,1744061318.594821,12.961477994918823,3.1415926530946106,1744061318.5948222,12.961477994918823,28.011762649528396,1744061318.594823,12.961477994918823,4.0336938382257855e-20,1744061318.5948238,12.961477994918823,4.6308088116912266e-10,1744061318.5948253,12.961477994918823,0.0,1744061318.5948262,12.961477994918823,-22627416997.969524,1744061318.5948272,12.961477994918823,0.0,1744061318.5948281,12.961477994918823,28284271247.461903
+1744061318.6147046,12.981483221054077,-5.747644876572703,1744061318.6147068,12.981483221054077,-27.946768295737943,1744061318.614709,12.981483221054077,0.021416487838947597,1744061318.6147113,12.981483221054077,-56568542383.615204,1744061318.6147122,12.981483221054077,0.065,1744061318.6147134,12.981483221054077,3.1415926530946106,1744061318.6147146,12.981483221054077,28.011762649528396,1744061318.6147153,12.981483221054077,4.0336938382257855e-20,1744061318.6147165,12.981483221054077,4.6308088116912266e-10,1744061318.6147177,12.981483221054077,0.0,1744061318.6147184,12.981483221054077,-22627416997.969524,1744061318.6147194,12.981483221054077,0.0,1744061318.6147206,12.981483221054077,28284271247.461903
+1744061318.6349304,13.001469612121582,-5.747644876572703,1744061318.6349323,13.001469612121582,-27.946768295737943,1744061318.6349342,13.001469612121582,0.021416487838947597,1744061318.6349363,13.001469612121582,-56568542383.615204,1744061318.6349373,13.001469612121582,0.065,1744061318.6349387,13.001469612121582,3.1415926530946106,1744061318.6349397,13.001469612121582,28.011762649528396,1744061318.6349404,13.001469612121582,4.0336938382257855e-20,1744061318.6349413,13.001469612121582,4.6308088116912266e-10,1744061318.6349428,13.001469612121582,0.0,1744061318.6349435,13.001469612121582,-22627416997.969524,1744061318.6349444,13.001469612121582,0.0,1744061318.6349456,13.001469612121582,28284271247.461903
+1744061318.6548808,13.02148985862732,-5.747644876572703,1744061318.6548827,13.02148985862732,-27.946768295737943,1744061318.654885,13.02148985862732,0.021416487838947597,1744061318.6548874,13.02148985862732,-56568542383.615204,1744061318.6548884,13.02148985862732,0.065,1744061318.6548896,13.02148985862732,3.1415926530946106,1744061318.6548905,13.02148985862732,28.011762649528396,1744061318.6548915,13.02148985862732,4.0336938382257855e-20,1744061318.6548924,13.02148985862732,4.6308088116912266e-10,1744061318.6548939,13.02148985862732,0.0,1744061318.6548948,13.02148985862732,-22627416997.969524,1744061318.6548958,13.02148985862732,0.0,1744061318.6548967,13.02148985862732,28284271247.461903
+1744061318.6747472,13.041494369506836,-5.747644876572703,1744061318.674749,13.041494369506836,-27.946768295737943,1744061318.6747513,13.041494369506836,0.021416487838947597,1744061318.6747532,13.041494369506836,-56568542383.615204,1744061318.6747544,13.041494369506836,0.065,1744061318.6747556,13.041494369506836,3.1415926530946106,1744061318.6747568,13.041494369506836,28.011762649528396,1744061318.6747577,13.041494369506836,4.0336938382257855e-20,1744061318.6747587,13.041494369506836,4.6308088116912266e-10,1744061318.6747596,13.041494369506836,0.0,1744061318.6747603,13.041494369506836,-22627416997.969524,1744061318.6747615,13.041494369506836,0.0,1744061318.6747625,13.041494369506836,28284271247.461903
+1744061318.694983,13.06148886680603,-5.747644876572703,1744061318.6949847,13.06148886680603,-27.946768295737943,1744061318.6949873,13.06148886680603,0.021416487838947597,1744061318.6949892,13.06148886680603,-56568542383.615204,1744061318.6949904,13.06148886680603,0.065,1744061318.6949916,13.06148886680603,3.1415926530946106,1744061318.6949928,13.06148886680603,28.011762649528396,1744061318.694994,13.06148886680603,4.0336938382257855e-20,1744061318.6949947,13.06148886680603,4.6308088116912266e-10,1744061318.6949959,13.06148886680603,0.0,1744061318.6949968,13.06148886680603,-22627416997.969524,1744061318.694998,13.06148886680603,0.0,1744061318.6949987,13.06148886680603,28284271247.461903
+1744061318.714699,13.081435680389404,-5.747644876572703,1744061318.714701,13.081435680389404,-27.946768295737943,1744061318.714703,13.081435680389404,0.021416487838947597,1744061318.7147052,13.081435680389404,-56568542383.615204,1744061318.7147062,13.081435680389404,0.065,1744061318.7147074,13.081435680389404,3.1415926530946106,1744061318.7147086,13.081435680389404,28.011762649528396,1744061318.7147095,13.081435680389404,4.0336938382257855e-20,1744061318.7147102,13.081435680389404,4.6308088116912266e-10,1744061318.7147117,13.081435680389404,0.0,1744061318.7147124,13.081435680389404,-22627416997.969524,1744061318.7147133,13.081435680389404,0.0,1744061318.714714,13.081435680389404,28284271247.461903
+1744061318.735474,13.10145616531372,-5.747644876572703,1744061318.735476,13.10145616531372,-27.946768295737943,1744061318.7354782,13.10145616531372,0.021416487838947597,1744061318.7354803,13.10145616531372,-56568542383.615204,1744061318.7354813,13.10145616531372,0.065,1744061318.7354827,13.10145616531372,3.1415926530946106,1744061318.7354836,13.10145616531372,28.011762649528396,1744061318.7354846,13.10145616531372,4.0336938382257855e-20,1744061318.7354856,13.10145616531372,4.6308088116912266e-10,1744061318.7354865,13.10145616531372,0.0,1744061318.7354875,13.10145616531372,-22627416997.969524,1744061318.7354884,13.10145616531372,0.0,1744061318.7354894,13.10145616531372,28284271247.461903
+1744061318.7546406,13.121439695358276,-5.747644876572703,1744061318.7546422,13.121439695358276,-27.946768295737943,1744061318.7546444,13.121439695358276,0.021416487838947597,1744061318.7546465,13.121439695358276,-56568542383.615204,1744061318.7546475,13.121439695358276,0.065,1744061318.754649,13.121439695358276,3.1415926530946106,1744061318.7546499,13.121439695358276,28.011762649528396,1744061318.7546508,13.121439695358276,4.0336938382257855e-20,1744061318.7546515,13.121439695358276,4.6308088116912266e-10,1744061318.754653,13.121439695358276,0.0,1744061318.7546537,13.121439695358276,-22627416997.969524,1744061318.7546546,13.121439695358276,0.0,1744061318.754656,13.121439695358276,28284271247.461903
+1744061318.7746356,13.141435146331787,-5.747644876572703,1744061318.7746372,13.141435146331787,-27.946768295737943,1744061318.7746398,13.141435146331787,0.021416487838947597,1744061318.774642,13.141435146331787,-56568542383.615204,1744061318.774643,13.141435146331787,0.065,1744061318.7746441,13.141435146331787,3.1415926530946106,1744061318.7746453,13.141435146331787,28.011762649528396,1744061318.7746463,13.141435146331787,4.0336938382257855e-20,1744061318.774647,13.141435146331787,4.6308088116912266e-10,1744061318.7746484,13.141435146331787,0.0,1744061318.7746491,13.141435146331787,-22627416997.969524,1744061318.77465,13.141435146331787,0.0,1744061318.7746508,13.141435146331787,28284271247.461903
+1744061318.7946396,13.16144061088562,-5.747644876572703,1744061318.7946415,13.16144061088562,-27.946768295737943,1744061318.7946436,13.16144061088562,0.021416487838947597,1744061318.7946458,13.16144061088562,-56568542383.615204,1744061318.7946467,13.16144061088562,0.065,1744061318.7946477,13.16144061088562,3.1415926530946106,1744061318.794649,13.16144061088562,28.011762649528396,1744061318.7946498,13.16144061088562,4.0336938382257855e-20,1744061318.7946506,13.16144061088562,4.6308088116912266e-10,1744061318.794652,13.16144061088562,0.0,1744061318.7946527,13.16144061088562,-22627416997.969524,1744061318.7946537,13.16144061088562,0.0,1744061318.7946544,13.16144061088562,28284271247.461903
+1744061318.8147724,13.181485176086426,-5.747644876572703,1744061318.8147743,13.181485176086426,-27.946768295737943,1744061318.814777,13.181485176086426,0.021416487838947597,1744061318.8147788,13.181485176086426,-56568542383.615204,1744061318.81478,13.181485176086426,0.065,1744061318.8147812,13.181485176086426,3.1415926530946106,1744061318.8147821,13.181485176086426,28.011762649528396,1744061318.8147833,13.181485176086426,4.0336938382257855e-20,1744061318.8147843,13.181485176086426,4.6308088116912266e-10,1744061318.8147852,13.181485176086426,0.0,1744061318.8147862,13.181485176086426,-22627416997.969524,1744061318.8147874,13.181485176086426,0.0,1744061318.814788,13.181485176086426,28284271247.461903
+1744061318.8351529,13.201505661010742,-5.963762884444283,1744061318.8351548,13.201505661010742,-29.03106048911041,1744061318.8351567,13.201505661010742,0.021416487838947597,1744061318.835159,13.201505661010742,-56568542383.615204,1744061318.83516,13.201505661010742,0.065,1744061318.8351614,13.201505661010742,3.1415926530754428,1744061318.8351624,13.201505661010742,29.096055938400873,1744061318.835163,13.201505661010742,4.189832072501624e-20,1744061318.835164,13.201505661010742,1.945067947862554e-10,1744061318.8351653,13.201505661010742,0.0,1744061318.8351662,13.201505661010742,-22627416997.969524,1744061318.8351672,13.201505661010742,0.0,1744061318.835168,13.201505661010742,28284271247.461903
+1744061318.8552597,13.22148871421814,-5.963762884444283,1744061318.8552625,13.22148871421814,-29.03106048911041,1744061318.8552656,13.22148871421814,0.021416487838947597,1744061318.8552678,13.22148871421814,-56568542383.615204,1744061318.8552692,13.22148871421814,0.065,1744061318.8552704,13.22148871421814,3.1415926530754428,1744061318.8552723,13.22148871421814,29.096055938400873,1744061318.8552732,13.22148871421814,4.189832072501624e-20,1744061318.8552742,13.22148871421814,1.945067947862554e-10,1744061318.8552756,13.22148871421814,0.0,1744061318.8552768,13.22148871421814,-22627416997.969524,1744061318.855278,13.22148871421814,0.0,1744061318.8552792,13.22148871421814,28284271247.461903
+1744061318.8746219,13.241463422775269,-5.963762884444283,1744061318.8746238,13.241463422775269,-29.03106048911041,1744061318.8746262,13.241463422775269,0.021416487838947597,1744061318.874628,13.241463422775269,-56568542383.615204,1744061318.8746293,13.241463422775269,0.065,1744061318.8746307,13.241463422775269,3.1415926530754428,1744061318.8746316,13.241463422775269,29.096055938400873,1744061318.8746324,13.241463422775269,4.189832072501624e-20,1744061318.8746336,13.241463422775269,1.945067947862554e-10,1744061318.8746345,13.241463422775269,0.0,1744061318.8746355,13.241463422775269,-22627416997.969524,1744061318.8746367,13.241463422775269,0.0,1744061318.8746374,13.241463422775269,28284271247.461903
+1744061318.8946695,13.261467218399048,-5.963762884444283,1744061318.8946714,13.261467218399048,-29.03106048911041,1744061318.8946736,13.261467218399048,0.021416487838947597,1744061318.8946757,13.261467218399048,-56568542383.615204,1744061318.8946767,13.261467218399048,0.065,1744061318.894678,13.261467218399048,3.1415926530754428,1744061318.894679,13.261467218399048,29.096055938400873,1744061318.89468,13.261467218399048,4.189832072501624e-20,1744061318.894681,13.261467218399048,1.945067947862554e-10,1744061318.8946822,13.261467218399048,0.0,1744061318.8946831,13.261467218399048,-22627416997.969524,1744061318.894684,13.261467218399048,0.0,1744061318.894685,13.261467218399048,28284271247.461903
+1744061318.9147403,13.28150200843811,-5.963762884444283,1744061318.914744,13.28150200843811,-29.03106048911041,1744061318.9147482,13.28150200843811,0.021416487838947597,1744061318.9147515,13.28150200843811,-56568542383.615204,1744061318.9147532,13.28150200843811,0.065,1744061318.9147558,13.28150200843811,3.1415926530754428,1744061318.914757,13.28150200843811,29.096055938400873,1744061318.9147582,13.28150200843811,4.189832072501624e-20,1744061318.914759,13.28150200843811,1.945067947862554e-10,1744061318.91476,13.28150200843811,0.0,1744061318.9147613,13.28150200843811,-22627416997.969524,1744061318.9147623,13.28150200843811,0.0,1744061318.914763,13.28150200843811,28284271247.461903
+1744061318.9348478,13.301438808441162,-5.963762884444283,1744061318.9348495,13.301438808441162,-29.03106048911041,1744061318.9348516,13.301438808441162,0.021416487838947597,1744061318.9348536,13.301438808441162,-56568542383.615204,1744061318.9348547,13.301438808441162,0.065,1744061318.934856,13.301438808441162,3.1415926530754428,1744061318.934857,13.301438808441162,29.096055938400873,1744061318.9348578,13.301438808441162,4.189832072501624e-20,1744061318.9348586,13.301438808441162,1.945067947862554e-10,1744061318.9348598,13.301438808441162,0.0,1744061318.9348605,13.301438808441162,-22627416997.969524,1744061318.9348617,13.301438808441162,0.0,1744061318.9348624,13.301438808441162,28284271247.461903
+1744061318.9552765,13.321537971496582,-5.963762884444283,1744061318.9552794,13.321537971496582,-29.03106048911041,1744061318.9552822,13.321537971496582,0.021416487838947597,1744061318.955284,13.321537971496582,-56568542383.615204,1744061318.9552855,13.321537971496582,0.065,1744061318.9552867,13.321537971496582,3.1415926530754428,1744061318.9552877,13.321537971496582,29.096055938400873,1744061318.9552886,13.321537971496582,4.189832072501624e-20,1744061318.9552898,13.321537971496582,1.945067947862554e-10,1744061318.955291,13.321537971496582,0.0,1744061318.9552922,13.321537971496582,-22627416997.969524,1744061318.9552937,13.321537971496582,0.0,1744061318.9552944,13.321537971496582,28284271247.461903
+1744061318.9748223,13.341540098190308,-5.963762884444283,1744061318.9748242,13.341540098190308,-29.03106048911041,1744061318.9748266,13.341540098190308,0.021416487838947597,1744061318.9748287,13.341540098190308,-56568542383.615204,1744061318.97483,13.341540098190308,0.065,1744061318.974831,13.341540098190308,3.1415926530754428,1744061318.9748323,13.341540098190308,29.096055938400873,1744061318.9748335,13.341540098190308,4.189832072501624e-20,1744061318.9748342,13.341540098190308,1.945067947862554e-10,1744061318.9748354,13.341540098190308,0.0,1744061318.974836,13.341540098190308,-22627416997.969524,1744061318.9748373,13.341540098190308,0.0,1744061318.974838,13.341540098190308,28284271247.461903
+1744061318.9946754,13.361475944519043,-5.963762884444283,1744061318.9946775,13.361475944519043,-29.03106048911041,1744061318.9946797,13.361475944519043,0.021416487838947597,1744061318.994682,13.361475944519043,-56568542383.615204,1744061318.994683,13.361475944519043,0.065,1744061318.9946847,13.361475944519043,3.1415926530754428,1744061318.9946856,13.361475944519043,29.096055938400873,1744061318.9946864,13.361475944519043,4.189832072501624e-20,1744061318.9946876,13.361475944519043,1.945067947862554e-10,1744061318.9946887,13.361475944519043,0.0,1744061318.9946895,13.361475944519043,-22627416997.969524,1744061318.9946907,13.361475944519043,0.0,1744061318.9946916,13.361475944519043,28284271247.461903
+1744061319.0147276,13.381473541259766,-5.963762884444283,1744061319.0147297,13.381473541259766,-29.03106048911041,1744061319.0147324,13.381473541259766,0.021416487838947597,1744061319.0147345,13.381473541259766,-56568542383.615204,1744061319.0147357,13.381473541259766,0.065,1744061319.014737,13.381473541259766,3.1415926530754428,1744061319.014738,13.381473541259766,29.096055938400873,1744061319.014739,13.381473541259766,4.189832072501624e-20,1744061319.01474,13.381473541259766,1.945067947862554e-10,1744061319.0147412,13.381473541259766,0.0,1744061319.0147424,13.381473541259766,-22627416997.969524,1744061319.0147433,13.381473541259766,0.0,1744061319.0147443,13.381473541259766,28284271247.461903
+1744061319.0348835,13.401468515396118,-5.963762884444283,1744061319.0348854,13.401468515396118,-29.03106048911041,1744061319.0348873,13.401468515396118,0.021416487838947597,1744061319.0348897,13.401468515396118,-56568542383.615204,1744061319.0348907,13.401468515396118,0.065,1744061319.0348923,13.401468515396118,3.1415926530754428,1744061319.0348933,13.401468515396118,29.096055938400873,1744061319.034894,13.401468515396118,4.189832072501624e-20,1744061319.0348952,13.401468515396118,1.945067947862554e-10,1744061319.0348961,13.401468515396118,0.0,1744061319.034897,13.401468515396118,-22627416997.969524,1744061319.0348983,13.401468515396118,0.0,1744061319.034899,13.401468515396118,28284271247.461903
+1744061319.055437,13.421501159667969,-5.963762884444283,1744061319.05544,13.421501159667969,-29.03106048911041,1744061319.0554442,13.421501159667969,0.021416487838947597,1744061319.055447,13.421501159667969,-56568542383.615204,1744061319.0554485,13.421501159667969,0.065,1744061319.0554507,13.421501159667969,3.1415926530754428,1744061319.0554533,13.421501159667969,29.096055938400873,1744061319.0554543,13.421501159667969,4.189832072501624e-20,1744061319.0554557,13.421501159667969,1.945067947862554e-10,1744061319.0554576,13.421501159667969,0.0,1744061319.0554593,13.421501159667969,-22627416997.969524,1744061319.055461,13.421501159667969,0.0,1744061319.0554621,13.421501159667969,28284271247.461903
+1744061319.0747359,13.441473007202148,-5.963762884444283,1744061319.0747375,13.441473007202148,-29.03106048911041,1744061319.0747402,13.441473007202148,0.021416487838947597,1744061319.0747423,13.441473007202148,-56568542383.615204,1744061319.0747433,13.441473007202148,0.065,1744061319.0747445,13.441473007202148,3.1415926530754428,1744061319.074746,13.441473007202148,29.096055938400873,1744061319.0747466,13.441473007202148,4.189832072501624e-20,1744061319.0747476,13.441473007202148,1.945067947862554e-10,1744061319.0747488,13.441473007202148,0.0,1744061319.0747497,13.441473007202148,-22627416997.969524,1744061319.074751,13.441473007202148,0.0,1744061319.074752,13.441473007202148,28284271247.461903
+1744061319.09466,13.461474895477295,-5.963762884444283,1744061319.094662,13.461474895477295,-29.03106048911041,1744061319.094664,13.461474895477295,0.021416487838947597,1744061319.0946665,13.461474895477295,-56568542383.615204,1744061319.0946674,13.461474895477295,0.065,1744061319.0946693,13.461474895477295,3.1415926530754428,1744061319.0946705,13.461474895477295,29.096055938400873,1744061319.0946712,13.461474895477295,4.189832072501624e-20,1744061319.0946724,13.461474895477295,1.945067947862554e-10,1744061319.0946734,13.461474895477295,0.0,1744061319.0946743,13.461474895477295,-22627416997.969524,1744061319.0946755,13.461474895477295,0.0,1744061319.0946763,13.461474895477295,28284271247.461903
+1744061319.1147697,13.4814772605896,-5.963762884444283,1744061319.1147714,13.4814772605896,-29.03106048911041,1744061319.1147738,13.4814772605896,0.021416487838947597,1744061319.114776,13.4814772605896,-56568542383.615204,1744061319.1147768,13.4814772605896,0.065,1744061319.114778,13.4814772605896,3.1415926530754428,1744061319.1147792,13.4814772605896,29.096055938400873,1744061319.11478,13.4814772605896,4.189832072501624e-20,1744061319.114781,13.4814772605896,1.945067947862554e-10,1744061319.1147819,13.4814772605896,0.0,1744061319.114783,13.4814772605896,-22627416997.969524,1744061319.114784,13.4814772605896,0.0,1744061319.1147847,13.4814772605896,28284271247.461903
+1744061319.134949,13.501460075378418,-5.963762884444283,1744061319.1349506,13.501460075378418,-29.03106048911041,1744061319.1349528,13.501460075378418,0.021416487838947597,1744061319.1349547,13.501460075378418,-56568542383.615204,1744061319.1349561,13.501460075378418,0.065,1744061319.134957,13.501460075378418,3.1415926530754428,1744061319.1349583,13.501460075378418,29.096055938400873,1744061319.1349595,13.501460075378418,4.189832072501624e-20,1744061319.1349602,13.501460075378418,1.945067947862554e-10,1744061319.1349614,13.501460075378418,0.0,1744061319.134962,13.501460075378418,-22627416997.969524,1744061319.1349633,13.501460075378418,0.0,1744061319.1349642,13.501460075378418,28284271247.461903
+1744061319.1553547,13.521501302719116,-5.963762884444283,1744061319.1553574,13.521501302719116,-29.03106048911041,1744061319.1553786,13.521501302719116,0.021416487838947597,1744061319.1553807,13.521501302719116,-56568542383.615204,1744061319.1553817,13.521501302719116,0.065,1744061319.1553833,13.521501302719116,3.1415926530754428,1744061319.1553843,13.521501302719116,29.096055938400873,1744061319.155385,13.521501302719116,4.189832072501624e-20,1744061319.1553864,13.521501302719116,1.945067947862554e-10,1744061319.1553876,13.521501302719116,0.0,1744061319.1553888,13.521501302719116,-22627416997.969524,1744061319.15539,13.521501302719116,0.0,1744061319.155391,13.521501302719116,28284271247.461903
+1744061319.1747274,13.541471004486084,-5.963762884444283,1744061319.174729,13.541471004486084,-29.03106048911041,1744061319.1747317,13.541471004486084,0.021416487838947597,1744061319.1747339,13.541471004486084,-56568542383.615204,1744061319.174735,13.541471004486084,0.065,1744061319.1747365,13.541471004486084,3.1415926530754428,1744061319.1747375,13.541471004486084,29.096055938400873,1744061319.1747382,13.541471004486084,4.189832072501624e-20,1744061319.1747394,13.541471004486084,1.945067947862554e-10,1744061319.1747406,13.541471004486084,0.0,1744061319.1747415,13.541471004486084,-22627416997.969524,1744061319.1747427,13.541471004486084,0.0,1744061319.174744,13.541471004486084,28284271247.461903
+1744061319.194669,13.561471700668335,-5.963762884444283,1744061319.1946712,13.561471700668335,-29.03106048911041,1744061319.194674,13.561471700668335,0.021416487838947597,1744061319.1946764,13.561471700668335,-56568542383.615204,1744061319.1946778,13.561471700668335,0.065,1744061319.194679,13.561471700668335,3.1415926530754428,1744061319.19468,13.561471700668335,29.096055938400873,1744061319.1946812,13.561471700668335,4.189832072501624e-20,1744061319.1946824,13.561471700668335,1.945067947862554e-10,1744061319.1946833,13.561471700668335,0.0,1744061319.1946845,13.561471700668335,-22627416997.969524,1744061319.1946855,13.561471700668335,0.0,1744061319.1946862,13.561471700668335,28284271247.461903
+1744061319.2146986,13.581469058990479,-5.963762884444283,1744061319.2147002,13.581469058990479,-29.03106048911041,1744061319.2147028,13.581469058990479,0.021416487838947597,1744061319.214705,13.581469058990479,-56568542383.615204,1744061319.2147062,13.581469058990479,0.065,1744061319.2147074,13.581469058990479,3.1415926530754428,1744061319.2147086,13.581469058990479,29.096055938400873,1744061319.2147095,13.581469058990479,4.189832072501624e-20,1744061319.2147102,13.581469058990479,1.945067947862554e-10,1744061319.2147117,13.581469058990479,0.0,1744061319.2147126,13.581469058990479,-22627416997.969524,1744061319.2147133,13.581469058990479,0.0,1744061319.2147143,13.581469058990479,28284271247.461903
+1744061319.2352448,13.601476669311523,-5.963762884444283,1744061319.2352464,13.601476669311523,-29.03106048911041,1744061319.2352486,13.601476669311523,0.021416487838947597,1744061319.2352507,13.601476669311523,-56568542383.615204,1744061319.2352517,13.601476669311523,0.065,1744061319.235253,13.601476669311523,3.1415926530754428,1744061319.235254,13.601476669311523,29.096055938400873,1744061319.235255,13.601476669311523,4.189832072501624e-20,1744061319.2352557,13.601476669311523,1.945067947862554e-10,1744061319.2352571,13.601476669311523,0.0,1744061319.235258,13.601476669311523,-22627416997.969524,1744061319.235259,13.601476669311523,0.0,1744061319.23526,13.601476669311523,28284271247.461903
+1744061319.254883,13.621506929397583,-5.963762884444283,1744061319.2548852,13.621506929397583,-29.03106048911041,1744061319.2548873,13.621506929397583,0.021416487838947597,1744061319.2548897,13.621506929397583,-56568542383.615204,1744061319.2548907,13.621506929397583,0.065,1744061319.254892,13.621506929397583,3.1415926530754428,1744061319.2548933,13.621506929397583,29.096055938400873,1744061319.254894,13.621506929397583,4.189832072501624e-20,1744061319.2548952,13.621506929397583,1.945067947862554e-10,1744061319.2548962,13.621506929397583,0.0,1744061319.254897,13.621506929397583,-22627416997.969524,1744061319.254898,13.621506929397583,0.0,1744061319.2548993,13.621506929397583,28284271247.461903
+1744061319.2746732,13.64144253730774,-5.963762884444283,1744061319.2746751,13.64144253730774,-29.03106048911041,1744061319.274678,13.64144253730774,0.021416487838947597,1744061319.2746804,13.64144253730774,-56568542383.615204,1744061319.2746813,13.64144253730774,0.065,1744061319.2746825,13.64144253730774,3.1415926530754428,1744061319.2746837,13.64144253730774,29.096055938400873,1744061319.2746847,13.64144253730774,4.189832072501624e-20,1744061319.2746856,13.64144253730774,1.945067947862554e-10,1744061319.2746868,13.64144253730774,0.0,1744061319.2746878,13.64144253730774,-22627416997.969524,1744061319.2746887,13.64144253730774,0.0,1744061319.2746897,13.64144253730774,28284271247.461903
+1744061319.2950947,13.661480188369751,-5.963762884444283,1744061319.2950974,13.661480188369751,-29.03106048911041,1744061319.2951005,13.661480188369751,0.021416487838947597,1744061319.2951028,13.661480188369751,-56568542383.615204,1744061319.295104,13.661480188369751,0.065,1744061319.2951055,13.661480188369751,3.1415926530754428,1744061319.2951071,13.661480188369751,29.096055938400873,1744061319.2951083,13.661480188369751,4.189832072501624e-20,1744061319.2951097,13.661480188369751,1.945067947862554e-10,1744061319.295111,13.661480188369751,0.0,1744061319.295112,13.661480188369751,-22627416997.969524,1744061319.2951128,13.661480188369751,0.0,1744061319.295114,13.661480188369751,28284271247.461903
+1744061319.3147347,13.681500434875488,-5.963762884444283,1744061319.3147368,13.681500434875488,-29.03106048911041,1744061319.3147407,13.681500434875488,0.021416487838947597,1744061319.3147433,13.681500434875488,-56568542383.615204,1744061319.3147452,13.681500434875488,0.065,1744061319.3147564,13.681500434875488,3.1415926530754428,1744061319.314758,13.681500434875488,29.096055938400873,1744061319.3147597,13.681500434875488,4.189832072501624e-20,1744061319.3147624,13.681500434875488,1.945067947862554e-10,1744061319.314764,13.681500434875488,0.0,1744061319.3147676,13.681500434875488,-22627416997.969524,1744061319.3147702,13.681500434875488,0.0,1744061319.3147717,13.681500434875488,28284271247.461903
+1744061319.33495,13.701444864273071,-6.0958635423730785,1744061319.3349516,13.701444864273071,-29.69688686089047,1744061319.3349538,13.701444864273071,0.021416487838947597,1744061319.3349557,13.701444864273071,-56568542383.615204,1744061319.334957,13.701444864273071,0.065,1744061319.334958,13.701444864273071,3.1415926530636726,1744061319.334959,13.701444864273071,29.761875625350335,1744061319.3349602,13.701444864273071,4.285710107839894e-20,1744061319.334961,13.701444864273071,1.1418401886262369e-10,1744061319.3349621,13.701444864273071,0.0,1744061319.3349628,13.701444864273071,-22627416997.969524,1744061319.334964,13.701444864273071,0.0,1744061319.334965,13.701444864273071,28284271247.461903
+1744061319.3549728,13.721446514129639,-6.0958635423730785,1744061319.354976,13.721446514129639,-29.69688686089047,1744061319.3549793,13.721446514129639,0.021416487838947597,1744061319.3549817,13.721446514129639,-56568542383.615204,1744061319.354983,13.721446514129639,0.065,1744061319.354985,13.721446514129639,3.1415926530636726,1744061319.3549864,13.721446514129639,29.761875625350335,1744061319.3549876,13.721446514129639,4.285710107839894e-20,1744061319.3549886,13.721446514129639,1.1418401886262369e-10,1744061319.35499,13.721446514129639,0.0,1744061319.354991,13.721446514129639,-22627416997.969524,1744061319.3549922,13.721446514129639,0.0,1744061319.3549933,13.721446514129639,28284271247.461903
+1744061319.3751056,13.741507291793823,-6.0958635423730785,1744061319.3751094,13.741507291793823,-29.69688686089047,1744061319.375113,13.741507291793823,0.021416487838947597,1744061319.3751166,13.741507291793823,-56568542383.615204,1744061319.3751178,13.741507291793823,0.065,1744061319.3751194,13.741507291793823,3.1415926530636726,1744061319.3751209,13.741507291793823,29.761875625350335,1744061319.3751218,13.741507291793823,4.285710107839894e-20,1744061319.3751235,13.741507291793823,1.1418401886262369e-10,1744061319.3751252,13.741507291793823,0.0,1744061319.3751268,13.741507291793823,-22627416997.969524,1744061319.3751285,13.741507291793823,0.0,1744061319.3751302,13.741507291793823,28284271247.461903
+1744061319.3947115,13.761490106582642,-6.0958635423730785,1744061319.3947134,13.761490106582642,-29.69688686089047,1744061319.3947158,13.761490106582642,0.021416487838947597,1744061319.3947182,13.761490106582642,-56568542383.615204,1744061319.3947191,13.761490106582642,0.065,1744061319.3947208,13.761490106582642,3.1415926530636726,1744061319.3947217,13.761490106582642,29.761875625350335,1744061319.3947227,13.761490106582642,4.285710107839894e-20,1744061319.3947237,13.761490106582642,1.1418401886262369e-10,1744061319.3947248,13.761490106582642,0.0,1744061319.3947258,13.761490106582642,-22627416997.969524,1744061319.394727,13.761490106582642,0.0,1744061319.394728,13.761490106582642,28284271247.461903
+1744061319.4146495,13.78146743774414,-6.0958635423730785,1744061319.4146516,13.78146743774414,-29.69688686089047,1744061319.414654,13.78146743774414,0.021416487838947597,1744061319.414656,13.78146743774414,-56568542383.615204,1744061319.414657,13.78146743774414,0.065,1744061319.4146583,13.78146743774414,3.1415926530636726,1744061319.4146595,13.78146743774414,29.761875625350335,1744061319.4146605,13.78146743774414,4.285710107839894e-20,1744061319.4146614,13.78146743774414,1.1418401886262369e-10,1744061319.4146626,13.78146743774414,0.0,1744061319.4146638,13.78146743774414,-22627416997.969524,1744061319.4146647,13.78146743774414,0.0,1744061319.4146657,13.78146743774414,28284271247.461903
+1744061319.4350293,13.801465272903442,-6.0958635423730785,1744061319.4350314,13.801465272903442,-29.69688686089047,1744061319.4350333,13.801465272903442,0.021416487838947597,1744061319.4350355,13.801465272903442,-56568542383.615204,1744061319.4350367,13.801465272903442,0.065,1744061319.435038,13.801465272903442,3.1415926530636726,1744061319.4350395,13.801465272903442,29.761875625350335,1744061319.4350402,13.801465272903442,4.285710107839894e-20,1744061319.4350412,13.801465272903442,1.1418401886262369e-10,1744061319.4350424,13.801465272903442,0.0,1744061319.4350433,13.801465272903442,-22627416997.969524,1744061319.4350443,13.801465272903442,0.0,1744061319.435045,13.801465272903442,28284271247.461903
+1744061319.4549568,13.821456909179688,-6.0958635423730785,1744061319.4549587,13.821456909179688,-29.69688686089047,1744061319.4549606,13.821456909179688,0.021416487838947597,1744061319.454963,13.821456909179688,-56568542383.615204,1744061319.454964,13.821456909179688,0.065,1744061319.4549654,13.821456909179688,3.1415926530636726,1744061319.4549663,13.821456909179688,29.761875625350335,1744061319.4549673,13.821456909179688,4.285710107839894e-20,1744061319.4549682,13.821456909179688,1.1418401886262369e-10,1744061319.4549694,13.821456909179688,0.0,1744061319.4549704,13.821456909179688,-22627416997.969524,1744061319.4549713,13.821456909179688,0.0,1744061319.4549723,13.821456909179688,28284271247.461903
+1744061319.4746544,13.841476678848267,-6.0958635423730785,1744061319.4746563,13.841476678848267,-29.69688686089047,1744061319.4746585,13.841476678848267,0.021416487838947597,1744061319.4746609,13.841476678848267,-56568542383.615204,1744061319.4746618,13.841476678848267,0.065,1744061319.4746633,13.841476678848267,3.1415926530636726,1744061319.4746642,13.841476678848267,29.761875625350335,1744061319.474665,13.841476678848267,4.285710107839894e-20,1744061319.4746659,13.841476678848267,1.1418401886262369e-10,1744061319.474667,13.841476678848267,0.0,1744061319.474668,13.841476678848267,-22627416997.969524,1744061319.474669,13.841476678848267,0.0,1744061319.47467,13.841476678848267,28284271247.461903
+1744061319.4948857,13.861477375030518,-6.0958635423730785,1744061319.4948876,13.861477375030518,-29.69688686089047,1744061319.4948905,13.861477375030518,0.021416487838947597,1744061319.4948928,13.861477375030518,-56568542383.615204,1744061319.494894,13.861477375030518,0.065,1744061319.4948955,13.861477375030518,3.1415926530636726,1744061319.4948967,13.861477375030518,29.761875625350335,1744061319.4948976,13.861477375030518,4.285710107839894e-20,1744061319.494899,13.861477375030518,1.1418401886262369e-10,1744061319.4949007,13.861477375030518,0.0,1744061319.4949017,13.861477375030518,-22627416997.969524,1744061319.4949028,13.861477375030518,0.0,1744061319.4949038,13.861477375030518,28284271247.461903
+1744061319.514651,13.881493091583252,-6.0958635423730785,1744061319.514653,13.881493091583252,-29.69688686089047,1744061319.5146556,13.881493091583252,0.021416487838947597,1744061319.5146577,13.881493091583252,-56568542383.615204,1744061319.514659,13.881493091583252,0.065,1744061319.5146601,13.881493091583252,3.1415926530636726,1744061319.514661,13.881493091583252,29.761875625350335,1744061319.514662,13.881493091583252,4.285710107839894e-20,1744061319.514663,13.881493091583252,1.1418401886262369e-10,1744061319.5146642,13.881493091583252,0.0,1744061319.5146654,13.881493091583252,-22627416997.969524,1744061319.5146666,13.881493091583252,0.0,1744061319.5146673,13.881493091583252,28284271247.461903
+1744061319.5356827,13.901525020599365,-6.0958635423730785,1744061319.5356858,13.901525020599365,-29.69688686089047,1744061319.5356886,13.901525020599365,0.021416487838947597,1744061319.535691,13.901525020599365,-56568542383.615204,1744061319.5356922,13.901525020599365,0.065,1744061319.5356936,13.901525020599365,3.1415926530636726,1744061319.5356956,13.901525020599365,29.761875625350335,1744061319.5357158,13.901525020599365,4.285710107839894e-20,1744061319.5357168,13.901525020599365,1.1418401886262369e-10,1744061319.5357187,13.901525020599365,0.0,1744061319.5357196,13.901525020599365,-22627416997.969524,1744061319.5357218,13.901525020599365,0.0,1744061319.5357232,13.901525020599365,28284271247.461903
+1744061319.5547924,13.921475172042847,-6.0958635423730785,1744061319.5547945,13.921475172042847,-29.69688686089047,1744061319.5547967,13.921475172042847,0.021416487838947597,1744061319.554799,13.921475172042847,-56568542383.615204,1744061319.5548,13.921475172042847,0.065,1744061319.5548015,13.921475172042847,3.1415926530636726,1744061319.5548027,13.921475172042847,29.761875625350335,1744061319.5548036,13.921475172042847,4.285710107839894e-20,1744061319.5548048,13.921475172042847,1.1418401886262369e-10,1744061319.5548058,13.921475172042847,0.0,1744061319.5548067,13.921475172042847,-22627416997.969524,1744061319.554808,13.921475172042847,0.0,1744061319.5548086,13.921475172042847,28284271247.461903
+1744061319.574654,13.941467523574829,-6.0958635423730785,1744061319.574656,13.941467523574829,-29.69688686089047,1744061319.5746584,13.941467523574829,0.021416487838947597,1744061319.5746603,13.941467523574829,-56568542383.615204,1744061319.5746617,13.941467523574829,0.065,1744061319.574663,13.941467523574829,3.1415926530636726,1744061319.5746639,13.941467523574829,29.761875625350335,1744061319.574665,13.941467523574829,4.285710107839894e-20,1744061319.5746658,13.941467523574829,1.1418401886262369e-10,1744061319.5746667,13.941467523574829,0.0,1744061319.5746677,13.941467523574829,-22627416997.969524,1744061319.574669,13.941467523574829,0.0,1744061319.5746696,13.941467523574829,28284271247.461903
+1744061319.5949395,13.961439609527588,-6.0958635423730785,1744061319.5949414,13.961439609527588,-29.69688686089047,1744061319.5949438,13.961439609527588,0.021416487838947597,1744061319.594946,13.961439609527588,-56568542383.615204,1744061319.594947,13.961439609527588,0.065,1744061319.5949483,13.961439609527588,3.1415926530636726,1744061319.5949497,13.961439609527588,29.761875625350335,1744061319.5949504,13.961439609527588,4.285710107839894e-20,1744061319.5949519,13.961439609527588,1.1418401886262369e-10,1744061319.5949533,13.961439609527588,0.0,1744061319.594954,13.961439609527588,-22627416997.969524,1744061319.5949552,13.961439609527588,0.0,1744061319.5949564,13.961439609527588,28284271247.461903
+1744061319.6146753,13.981472253799438,-6.0958635423730785,1744061319.614677,13.981472253799438,-29.69688686089047,1744061319.6146793,13.981472253799438,0.021416487838947597,1744061319.6146815,13.981472253799438,-56568542383.615204,1744061319.6146827,13.981472253799438,0.065,1744061319.6146839,13.981472253799438,3.1415926530636726,1744061319.6146853,13.981472253799438,29.761875625350335,1744061319.614686,13.981472253799438,4.285710107839894e-20,1744061319.614687,13.981472253799438,1.1418401886262369e-10,1744061319.6146882,13.981472253799438,0.0,1744061319.614689,13.981472253799438,-22627416997.969524,1744061319.61469,13.981472253799438,0.0,1744061319.614691,13.981472253799438,28284271247.461903
+1744061319.6348577,14.001471757888794,-6.0958635423730785,1744061319.6348593,14.001471757888794,-29.69688686089047,1744061319.6348615,14.001471757888794,0.021416487838947597,1744061319.6348639,14.001471757888794,-56568542383.615204,1744061319.6348648,14.001471757888794,0.065,1744061319.6348662,14.001471757888794,3.1415926530636726,1744061319.6348672,14.001471757888794,29.761875625350335,1744061319.6348681,14.001471757888794,4.285710107839894e-20,1744061319.634869,14.001471757888794,1.1418401886262369e-10,1744061319.6348703,14.001471757888794,0.0,1744061319.6348712,14.001471757888794,-22627416997.969524,1744061319.6348724,14.001471757888794,0.0,1744061319.6348734,14.001471757888794,28284271247.461903
+1744061319.6554356,14.021484375,-6.0958635423730785,1744061319.6554377,14.021484375,-29.69688686089047,1744061319.6554408,14.021484375,0.021416487838947597,1744061319.6554635,14.021484375,-56568542383.615204,1744061319.655465,14.021484375,0.065,1744061319.6554666,14.021484375,3.1415926530636726,1744061319.655468,14.021484375,29.761875625350335,1744061319.6554694,14.021484375,4.285710107839894e-20,1744061319.6554706,14.021484375,1.1418401886262369e-10,1744061319.655491,14.021484375,0.0,1744061319.6554928,14.021484375,-22627416997.969524,1744061319.6554947,14.021484375,0.0,1744061319.6554961,14.021484375,28284271247.461903
+1744061319.6746173,14.04144549369812,-6.0958635423730785,1744061319.6746192,14.04144549369812,-29.69688686089047,1744061319.6746213,14.04144549369812,0.021416487838947597,1744061319.6746237,14.04144549369812,-56568542383.615204,1744061319.6746247,14.04144549369812,0.065,1744061319.6746264,14.04144549369812,3.1415926530636726,1744061319.6746273,14.04144549369812,29.761875625350335,1744061319.674628,14.04144549369812,4.285710107839894e-20,1744061319.6746292,14.04144549369812,1.1418401886262369e-10,1744061319.6746302,14.04144549369812,0.0,1744061319.674631,14.04144549369812,-22627416997.969524,1744061319.6746323,14.04144549369812,0.0,1744061319.674633,14.04144549369812,28284271247.461903
+1744061319.6947966,14.061484098434448,-6.0958635423730785,1744061319.6947982,14.061484098434448,-29.69688686089047,1744061319.6948006,14.061484098434448,0.021416487838947597,1744061319.694803,14.061484098434448,-56568542383.615204,1744061319.694804,14.061484098434448,0.065,1744061319.6948051,14.061484098434448,3.1415926530636726,1744061319.6948063,14.061484098434448,29.761875625350335,1744061319.694807,14.061484098434448,4.285710107839894e-20,1744061319.694808,14.061484098434448,1.1418401886262369e-10,1744061319.6948092,14.061484098434448,0.0,1744061319.6948102,14.061484098434448,-22627416997.969524,1744061319.694811,14.061484098434448,0.0,1744061319.6948118,14.061484098434448,28284271247.461903
+1744061319.7147155,14.081473112106323,-6.0958635423730785,1744061319.7147171,14.081473112106323,-29.69688686089047,1744061319.7147198,14.081473112106323,0.021416487838947597,1744061319.7147217,14.081473112106323,-56568542383.615204,1744061319.7147229,14.081473112106323,0.065,1744061319.714724,14.081473112106323,3.1415926530636726,1744061319.7147255,14.081473112106323,29.761875625350335,1744061319.7147262,14.081473112106323,4.285710107839894e-20,1744061319.7147274,14.081473112106323,1.1418401886262369e-10,1744061319.7147286,14.081473112106323,0.0,1744061319.7147298,14.081473112106323,-22627416997.969524,1744061319.7147307,14.081473112106323,0.0,1744061319.7147315,14.081473112106323,28284271247.461903
+1744061319.7348585,14.101468086242676,-6.0958635423730785,1744061319.7348602,14.101468086242676,-29.69688686089047,1744061319.7348626,14.101468086242676,0.021416487838947597,1744061319.734865,14.101468086242676,-56568542383.615204,1744061319.734866,14.101468086242676,0.065,1744061319.734867,14.101468086242676,3.1415926530636726,1744061319.7348683,14.101468086242676,29.761875625350335,1744061319.7348692,14.101468086242676,4.285710107839894e-20,1744061319.7348702,14.101468086242676,1.1418401886262369e-10,1744061319.7348714,14.101468086242676,0.0,1744061319.7348723,14.101468086242676,-22627416997.969524,1744061319.7348733,14.101468086242676,0.0,1744061319.734874,14.101468086242676,28284271247.461903
+1744061319.7550867,14.121482372283936,-6.0958635423730785,1744061319.7550886,14.121482372283936,-29.69688686089047,1744061319.7550912,14.121482372283936,0.021416487838947597,1744061319.7550933,14.121482372283936,-56568542383.615204,1744061319.7550945,14.121482372283936,0.065,1744061319.7550957,14.121482372283936,3.1415926530636726,1744061319.755097,14.121482372283936,29.761875625350335,1744061319.7550979,14.121482372283936,4.285710107839894e-20,1744061319.7550986,14.121482372283936,1.1418401886262369e-10,1744061319.7551,14.121482372283936,0.0,1744061319.755101,14.121482372283936,-22627416997.969524,1744061319.755102,14.121482372283936,0.0,1744061319.7551029,14.121482372283936,28284271247.461903
+1744061319.774723,14.141436338424683,-6.0958635423730785,1744061319.774725,14.141436338424683,-29.69688686089047,1744061319.774727,14.141436338424683,0.021416487838947597,1744061319.7747293,14.141436338424683,-56568542383.615204,1744061319.7747302,14.141436338424683,0.065,1744061319.7747316,14.141436338424683,3.1415926530636726,1744061319.7747326,14.141436338424683,29.761875625350335,1744061319.7747335,14.141436338424683,4.285710107839894e-20,1744061319.7747347,14.141436338424683,1.1418401886262369e-10,1744061319.774736,14.141436338424683,0.0,1744061319.774737,14.141436338424683,-22627416997.969524,1744061319.7747378,14.141436338424683,0.0,1744061319.774739,14.141436338424683,28284271247.461903
+1744061319.794657,14.161457061767578,-6.0958635423730785,1744061319.794659,14.161457061767578,-29.69688686089047,1744061319.7946613,14.161457061767578,0.021416487838947597,1744061319.7946634,14.161457061767578,-56568542383.615204,1744061319.7946646,14.161457061767578,0.065,1744061319.794666,14.161457061767578,3.1415926530636726,1744061319.794667,14.161457061767578,29.761875625350335,1744061319.794668,14.161457061767578,4.285710107839894e-20,1744061319.7946692,14.161457061767578,1.1418401886262369e-10,1744061319.79467,14.161457061767578,0.0,1744061319.7946708,14.161457061767578,-22627416997.969524,1744061319.794672,14.161457061767578,0.0,1744061319.794673,14.161457061767578,28284271247.461903
+1744061319.8146713,14.181440591812134,-6.0958635423730785,1744061319.8146732,14.181440591812134,-29.69688686089047,1744061319.8146756,14.181440591812134,0.021416487838947597,1744061319.8146775,14.181440591812134,-56568542383.615204,1744061319.8146787,14.181440591812134,0.065,1744061319.8146799,14.181440591812134,3.1415926530636726,1744061319.8146808,14.181440591812134,29.761875625350335,1744061319.8146818,14.181440591812134,4.285710107839894e-20,1744061319.8146827,14.181440591812134,1.1418401886262369e-10,1744061319.814684,14.181440591812134,0.0,1744061319.8146846,14.181440591812134,-22627416997.969524,1744061319.8146856,14.181440591812134,0.0,1744061319.8146865,14.181440591812134,28284271247.461903
+1744061319.834824,14.201435089111328,-6.172693611215479,1744061319.834826,14.201435089111328,-30.001127536584324,1744061319.8348281,14.201435089111328,0.021416487838947597,1744061319.8348303,14.201435089111328,-56568542383.615204,1744061319.8348315,14.201435089111328,0.065,1744061319.8348327,14.201435089111328,3.1415926530582943,1744061319.8348336,14.201435089111328,30.066121860951966,1744061319.8348346,14.201435089111328,4.329521565960144e-20,1744061319.8348355,14.201435089111328,8.951572955361499e-11,1744061319.8348367,14.201435089111328,0.0,1744061319.8348377,14.201435089111328,-22627416997.969524,1744061319.8348389,14.201435089111328,0.0,1744061319.8348396,14.201435089111328,28284271247.461903
+1744061319.8554747,14.221490383148193,-6.172693611215479,1744061319.8554785,14.221490383148193,-30.001127536584324,1744061319.8554819,14.221490383148193,0.021416487838947597,1744061319.8554852,14.221490383148193,-56568542383.615204,1744061319.8554864,14.221490383148193,0.065,1744061319.8554885,14.221490383148193,3.1415926530582943,1744061319.8554897,14.221490383148193,30.066121860951966,1744061319.8554914,14.221490383148193,4.329521565960144e-20,1744061319.8554928,14.221490383148193,8.951572955361499e-11,1744061319.8554947,14.221490383148193,0.0,1744061319.855496,14.221490383148193,-22627416997.969524,1744061319.855497,14.221490383148193,0.0,1744061319.855498,14.221490383148193,28284271247.461903
+1744061319.8748667,14.241457462310791,-6.172693611215479,1744061319.8748686,14.241457462310791,-30.001127536584324,1744061319.8748713,14.241457462310791,0.021416487838947597,1744061319.8748736,14.241457462310791,-56568542383.615204,1744061319.8748746,14.241457462310791,0.065,1744061319.874876,14.241457462310791,3.1415926530582943,1744061319.874877,14.241457462310791,30.066121860951966,1744061319.874878,14.241457462310791,4.329521565960144e-20,1744061319.8748786,14.241457462310791,8.951572955361499e-11,1744061319.87488,14.241457462310791,0.0,1744061319.874881,14.241457462310791,-22627416997.969524,1744061319.874882,14.241457462310791,0.0,1744061319.8748832,14.241457462310791,28284271247.461903
+1744061319.8946354,14.261467218399048,-6.172693611215479,1744061319.8946373,14.261467218399048,-30.001127536584324,1744061319.8946397,14.261467218399048,0.021416487838947597,1744061319.8946419,14.261467218399048,-56568542383.615204,1744061319.8946428,14.261467218399048,0.065,1744061319.8946443,14.261467218399048,3.1415926530582943,1744061319.8946452,14.261467218399048,30.066121860951966,1744061319.8946462,14.261467218399048,4.329521565960144e-20,1744061319.8946474,14.261467218399048,8.951572955361499e-11,1744061319.8946483,14.261467218399048,0.0,1744061319.8946493,14.261467218399048,-22627416997.969524,1744061319.8946505,14.261467218399048,0.0,1744061319.8946514,14.261467218399048,28284271247.461903
+1744061319.914671,14.28146767616272,-6.172693611215479,1744061319.9146726,14.28146767616272,-30.001127536584324,1744061319.9146752,14.28146767616272,0.021416487838947597,1744061319.9146771,14.28146767616272,-56568542383.615204,1744061319.9146783,14.28146767616272,0.065,1744061319.9146795,14.28146767616272,3.1415926530582943,1744061319.9146805,14.28146767616272,30.066121860951966,1744061319.9146817,14.28146767616272,4.329521565960144e-20,1744061319.9146826,14.28146767616272,8.951572955361499e-11,1744061319.9146836,14.28146767616272,0.0,1744061319.9146848,14.28146767616272,-22627416997.969524,1744061319.9146857,14.28146767616272,0.0,1744061319.9146864,14.28146767616272,28284271247.461903
+1744061319.9348555,14.30143690109253,-6.172693611215479,1744061319.9348571,14.30143690109253,-30.001127536584324,1744061319.9348593,14.30143690109253,0.021416487838947597,1744061319.9348617,14.30143690109253,-56568542383.615204,1744061319.9348626,14.30143690109253,0.065,1744061319.9348638,14.30143690109253,3.1415926530582943,1744061319.9348652,14.30143690109253,30.066121860951966,1744061319.934866,14.30143690109253,4.329521565960144e-20,1744061319.934867,14.30143690109253,8.951572955361499e-11,1744061319.9348683,14.30143690109253,0.0,1744061319.934869,14.30143690109253,-22627416997.969524,1744061319.9348702,14.30143690109253,0.0,1744061319.934871,14.30143690109253,28284271247.461903
+1744061319.9555352,14.321498394012451,-6.172693611215479,1744061319.9555385,14.321498394012451,-30.001127536584324,1744061319.9555426,14.321498394012451,0.021416487838947597,1744061319.9555457,14.321498394012451,-56568542383.615204,1744061319.9555473,14.321498394012451,0.065,1744061319.955549,14.321498394012451,3.1415926530582943,1744061319.955551,14.321498394012451,30.066121860951966,1744061319.955552,14.321498394012451,4.329521565960144e-20,1744061319.9555533,14.321498394012451,8.951572955361499e-11,1744061319.9555554,14.321498394012451,0.0,1744061319.9555564,14.321498394012451,-22627416997.969524,1744061319.9555578,14.321498394012451,0.0,1744061319.9555593,14.321498394012451,28284271247.461903
+1744061319.9747448,14.341441869735718,-6.172693611215479,1744061319.974747,14.341441869735718,-30.001127536584324,1744061319.9747493,14.341441869735718,0.021416487838947597,1744061319.9747517,14.341441869735718,-56568542383.615204,1744061319.9747527,14.341441869735718,0.065,1744061319.974754,14.341441869735718,3.1415926530582943,1744061319.974755,14.341441869735718,30.066121860951966,1744061319.974756,14.341441869735718,4.329521565960144e-20,1744061319.974757,14.341441869735718,8.951572955361499e-11,1744061319.9747581,14.341441869735718,0.0,1744061319.9747589,14.341441869735718,-22627416997.969524,1744061319.9747598,14.341441869735718,0.0,1744061319.974761,14.341441869735718,28284271247.461903
+1744061319.9947472,14.361438989639282,-6.172693611215479,1744061319.99475,14.361438989639282,-30.001127536584324,1744061319.9947524,14.361438989639282,0.021416487838947597,1744061319.9947546,14.361438989639282,-56568542383.615204,1744061319.994756,14.361438989639282,0.065,1744061319.9947574,14.361438989639282,3.1415926530582943,1744061319.9947584,14.361438989639282,30.066121860951966,1744061319.9947593,14.361438989639282,4.329521565960144e-20,1744061319.9947605,14.361438989639282,8.951572955361499e-11,1744061319.9947617,14.361438989639282,0.0,1744061319.994763,14.361438989639282,-22627416997.969524,1744061319.994764,14.361438989639282,0.0,1744061319.994765,14.361438989639282,28284271247.461903
+1744061320.0147686,14.381444454193115,-6.172693611215479,1744061320.014771,14.381444454193115,-30.001127536584324,1744061320.0147738,14.381444454193115,0.021416487838947597,1744061320.014776,14.381444454193115,-56568542383.615204,1744061320.0147777,14.381444454193115,0.065,1744061320.0147793,14.381444454193115,3.1415926530582943,1744061320.0147805,14.381444454193115,30.066121860951966,1744061320.0147815,14.381444454193115,4.329521565960144e-20,1744061320.0147827,14.381444454193115,8.951572955361499e-11,1744061320.0147839,14.381444454193115,0.0,1744061320.0147848,14.381444454193115,-22627416997.969524,1744061320.0147858,14.381444454193115,0.0,1744061320.0147867,14.381444454193115,28284271247.461903
+1744061320.0357385,14.401470422744751,-6.172693611215479,1744061320.0357406,14.401470422744751,-30.001127536584324,1744061320.0357435,14.401470422744751,0.021416487838947597,1744061320.035746,14.401470422744751,-56568542383.615204,1744061320.0357473,14.401470422744751,0.065,1744061320.0357487,14.401470422744751,3.1415926530582943,1744061320.03575,14.401470422744751,30.066121860951966,1744061320.0357509,14.401470422744751,4.329521565960144e-20,1744061320.0357518,14.401470422744751,8.951572955361499e-11,1744061320.0357535,14.401470422744751,0.0,1744061320.0357542,14.401470422744751,-22627416997.969524,1744061320.0357556,14.401470422744751,0.0,1744061320.0357566,14.401470422744751,28284271247.461903
+1744061320.054735,14.421467781066895,-6.172693611215479,1744061320.0547366,14.421467781066895,-30.001127536584324,1744061320.0547392,14.421467781066895,0.021416487838947597,1744061320.0547416,14.421467781066895,-56568542383.615204,1744061320.0547426,14.421467781066895,0.065,1744061320.054744,14.421467781066895,3.1415926530582943,1744061320.0547452,14.421467781066895,30.066121860951966,1744061320.054746,14.421467781066895,4.329521565960144e-20,1744061320.0547469,14.421467781066895,8.951572955361499e-11,1744061320.0547478,14.421467781066895,0.0,1744061320.054749,14.421467781066895,-22627416997.969524,1744061320.05475,14.421467781066895,0.0,1744061320.0547507,14.421467781066895,28284271247.461903
+1744061320.0746815,14.441437005996704,-6.172693611215479,1744061320.0746834,14.441437005996704,-30.001127536584324,1744061320.0746858,14.441437005996704,0.021416487838947597,1744061320.074688,14.441437005996704,-56568542383.615204,1744061320.0746894,14.441437005996704,0.065,1744061320.0746975,14.441437005996704,3.1415926530582943,1744061320.0746984,14.441437005996704,30.066121860951966,1744061320.0746994,14.441437005996704,4.329521565960144e-20,1744061320.0747006,14.441437005996704,8.951572955361499e-11,1744061320.0747015,14.441437005996704,0.0,1744061320.0747025,14.441437005996704,-22627416997.969524,1744061320.0747037,14.441437005996704,0.0,1744061320.0747044,14.441437005996704,28284271247.461903
+1744061320.0946903,14.461463212966919,-6.172693611215479,1744061320.094692,14.461463212966919,-30.001127536584324,1744061320.0946944,14.461463212966919,0.021416487838947597,1744061320.0946968,14.461463212966919,-56568542383.615204,1744061320.0946977,14.461463212966919,0.065,1744061320.094699,14.461463212966919,3.1415926530582943,1744061320.0947,14.461463212966919,30.066121860951966,1744061320.094701,14.461463212966919,4.329521565960144e-20,1744061320.094702,14.461463212966919,8.951572955361499e-11,1744061320.0947032,14.461463212966919,0.0,1744061320.0947042,14.461463212966919,-22627416997.969524,1744061320.0947053,14.461463212966919,0.0,1744061320.0947065,14.461463212966919,28284271247.461903
+1744061320.114658,14.481467723846436,-6.172693611215479,1744061320.11466,14.481467723846436,-30.001127536584324,1744061320.1146622,14.481467723846436,0.021416487838947597,1744061320.1146646,14.481467723846436,-56568542383.615204,1744061320.1146655,14.481467723846436,0.065,1744061320.1146667,14.481467723846436,3.1415926530582943,1744061320.114668,14.481467723846436,30.066121860951966,1744061320.1146688,14.481467723846436,4.329521565960144e-20,1744061320.1146698,14.481467723846436,8.951572955361499e-11,1744061320.1146708,14.481467723846436,0.0,1744061320.114672,14.481467723846436,-22627416997.969524,1744061320.1146731,14.481467723846436,0.0,1744061320.1146739,14.481467723846436,28284271247.461903
+1744061320.1348677,14.501434564590454,-6.172693611215479,1744061320.1348696,14.501434564590454,-30.001127536584324,1744061320.1348715,14.501434564590454,0.021416487838947597,1744061320.1348739,14.501434564590454,-56568542383.615204,1744061320.1348748,14.501434564590454,0.065,1744061320.1348763,14.501434564590454,3.1415926530582943,1744061320.1348774,14.501434564590454,30.066121860951966,1744061320.1348782,14.501434564590454,4.329521565960144e-20,1744061320.1348794,14.501434564590454,8.951572955361499e-11,1744061320.1348805,14.501434564590454,0.0,1744061320.1348813,14.501434564590454,-22627416997.969524,1744061320.1348822,14.501434564590454,0.0,1744061320.1348834,14.501434564590454,28284271247.461903
+1744061320.1548002,14.521448135375977,-6.172693611215479,1744061320.154802,14.521448135375977,-30.001127536584324,1744061320.1548047,14.521448135375977,0.021416487838947597,1744061320.154807,14.521448135375977,-56568542383.615204,1744061320.154808,14.521448135375977,0.065,1744061320.1548092,14.521448135375977,3.1415926530582943,1744061320.1548107,14.521448135375977,30.066121860951966,1744061320.1548114,14.521448135375977,4.329521565960144e-20,1744061320.1548123,14.521448135375977,8.951572955361499e-11,1744061320.1548138,14.521448135375977,0.0,1744061320.1548145,14.521448135375977,-22627416997.969524,1744061320.1548154,14.521448135375977,0.0,1744061320.1548166,14.521448135375977,28284271247.461903
+1744061320.1748142,14.54143500328064,-6.172693611215479,1744061320.1748164,14.54143500328064,-30.001127536584324,1744061320.1748188,14.54143500328064,0.021416487838947597,1744061320.174821,14.54143500328064,-56568542383.615204,1744061320.174822,14.54143500328064,0.065,1744061320.1748235,14.54143500328064,3.1415926530582943,1744061320.1748247,14.54143500328064,30.066121860951966,1744061320.1748254,14.54143500328064,4.329521565960144e-20,1744061320.1748264,14.54143500328064,8.951572955361499e-11,1744061320.1748278,14.54143500328064,0.0,1744061320.1748285,14.54143500328064,-22627416997.969524,1744061320.1748297,14.54143500328064,0.0,1744061320.174831,14.54143500328064,28284271247.461903
+1744061320.1947196,14.561464786529541,-6.172693611215479,1744061320.1947215,14.561464786529541,-30.001127536584324,1744061320.1947236,14.561464786529541,0.021416487838947597,1744061320.1947255,14.561464786529541,-56568542383.615204,1744061320.1947267,14.561464786529541,0.065,1744061320.194728,14.561464786529541,3.1415926530582943,1744061320.1947293,14.561464786529541,30.066121860951966,1744061320.19473,14.561464786529541,4.329521565960144e-20,1744061320.194731,14.561464786529541,8.951572955361499e-11,1744061320.194732,14.561464786529541,0.0,1744061320.1947331,14.561464786529541,-22627416997.969524,1744061320.1947343,14.561464786529541,0.0,1744061320.1947353,14.561464786529541,28284271247.461903
+1744061320.2146368,14.581436395645142,-6.172693611215479,1744061320.214639,14.581436395645142,-30.001127536584324,1744061320.214641,14.581436395645142,0.021416487838947597,1744061320.2146432,14.581436395645142,-56568542383.615204,1744061320.2146442,14.581436395645142,0.065,1744061320.214646,14.581436395645142,3.1415926530582943,1744061320.214647,14.581436395645142,30.066121860951966,1744061320.2146478,14.581436395645142,4.329521565960144e-20,1744061320.2146487,14.581436395645142,8.951572955361499e-11,1744061320.21465,14.581436395645142,0.0,1744061320.2146509,14.581436395645142,-22627416997.969524,1744061320.2146518,14.581436395645142,0.0,1744061320.214653,14.581436395645142,28284271247.461903
+1744061320.2349563,14.601437091827393,-6.172693611215479,1744061320.2349584,14.601437091827393,-30.001127536584324,1744061320.2349603,14.601437091827393,0.021416487838947597,1744061320.2349663,14.601437091827393,-56568542383.615204,1744061320.2349675,14.601437091827393,0.065,1744061320.2349691,14.601437091827393,3.1415926530582943,1744061320.23497,14.601437091827393,30.066121860951966,1744061320.2349708,14.601437091827393,4.329521565960144e-20,1744061320.234972,14.601437091827393,8.951572955361499e-11,1744061320.234973,14.601437091827393,0.0,1744061320.234974,14.601437091827393,-22627416997.969524,1744061320.2349746,14.601437091827393,0.0,1744061320.2349758,14.601437091827393,28284271247.461903
+1744061320.2557447,14.621501207351685,-6.172693611215479,1744061320.25575,14.621501207351685,-30.001127536584324,1744061320.2557566,14.621501207351685,0.021416487838947597,1744061320.2557614,14.621501207351685,-56568542383.615204,1744061320.2557635,14.621501207351685,0.065,1744061320.2557669,14.621501207351685,3.1415926530582943,1744061320.2557693,14.621501207351685,30.066121860951966,1744061320.2557716,14.621501207351685,4.329521565960144e-20,1744061320.2557743,14.621501207351685,8.951572955361499e-11,1744061320.255777,14.621501207351685,0.0,1744061320.2557788,14.621501207351685,-22627416997.969524,1744061320.2557817,14.621501207351685,0.0,1744061320.2557843,14.621501207351685,28284271247.461903
+1744061320.274668,14.641439437866211,-6.172693611215479,1744061320.2746701,14.641439437866211,-30.001127536584324,1744061320.274673,14.641439437866211,0.021416487838947597,1744061320.274675,14.641439437866211,-56568542383.615204,1744061320.2746763,14.641439437866211,0.065,1744061320.2746775,14.641439437866211,3.1415926530582943,1744061320.2746785,14.641439437866211,30.066121860951966,1744061320.2746797,14.641439437866211,4.329521565960144e-20,1744061320.2746806,14.641439437866211,8.951572955361499e-11,1744061320.2746816,14.641439437866211,0.0,1744061320.2746825,14.641439437866211,-22627416997.969524,1744061320.2746837,14.641439437866211,0.0,1744061320.2746847,14.641439437866211,28284271247.461903
+1744061320.2949622,14.661439657211304,-6.172693611215479,1744061320.2949643,14.661439657211304,-30.001127536584324,1744061320.2949665,14.661439657211304,0.021416487838947597,1744061320.2949693,14.661439657211304,-56568542383.615204,1744061320.294971,14.661439657211304,0.065,1744061320.2949724,14.661439657211304,3.1415926530582943,1744061320.2949734,14.661439657211304,30.066121860951966,1744061320.2949743,14.661439657211304,4.329521565960144e-20,1744061320.2949755,14.661439657211304,8.951572955361499e-11,1744061320.2949767,14.661439657211304,0.0,1744061320.294978,14.661439657211304,-22627416997.969524,1744061320.2949793,14.661439657211304,0.0,1744061320.2949803,14.661439657211304,28284271247.461903
+1744061320.3149307,14.681442737579346,-6.172693611215479,1744061320.3149328,14.681442737579346,-30.001127536584324,1744061320.314935,14.681442737579346,0.021416487838947597,1744061320.3149374,14.681442737579346,-56568542383.615204,1744061320.3149383,14.681442737579346,0.065,1744061320.3149397,14.681442737579346,3.1415926530582943,1744061320.3149407,14.681442737579346,30.066121860951966,1744061320.3149416,14.681442737579346,4.329521565960144e-20,1744061320.3149424,14.681442737579346,8.951572955361499e-11,1744061320.3149438,14.681442737579346,0.0,1744061320.3149445,14.681442737579346,-22627416997.969524,1744061320.3149457,14.681442737579346,0.0,1744061320.3149467,14.681442737579346,28284271247.461903
+1744061320.3350203,14.701524257659912,-6.180281567285573,1744061320.335022,14.701524257659912,-30.034820314933942,1744061320.3350244,14.701524257659912,0.021416487838947597,1744061320.3350265,14.701524257659912,-56568542383.615204,1744061320.3350275,14.701524257659912,0.065,1744061320.335029,14.701524257659912,3.1415926530576987,1744061320.33503,14.701524257659912,30.09980976467148,1744061320.3350308,14.701524257659912,4.334372624117067e-20,1744061320.3350317,14.701524257659912,8.713547017762556e-11,1744061320.335033,14.701524257659912,0.0,1744061320.335034,14.701524257659912,-22627416997.969524,1744061320.3350348,14.701524257659912,0.0,1744061320.3350358,14.701524257659912,28284271247.461903
+1744061320.355116,14.721438646316528,-6.180281567285573,1744061320.355118,14.721438646316528,-30.034820314933942,1744061320.3551207,14.721438646316528,0.021416487838947597,1744061320.355123,14.721438646316528,-56568542383.615204,1744061320.3551242,14.721438646316528,0.065,1744061320.3551438,14.721438646316528,3.1415926530576987,1744061320.3551447,14.721438646316528,30.09980976467148,1744061320.3551455,14.721438646316528,4.334372624117067e-20,1744061320.3551464,14.721438646316528,8.713547017762556e-11,1744061320.3551478,14.721438646316528,0.0,1744061320.3551488,14.721438646316528,-22627416997.969524,1744061320.3551497,14.721438646316528,0.0,1744061320.355151,14.721438646316528,28284271247.461903
+1744061320.3746724,14.74143671989441,-6.180281567285573,1744061320.374674,14.74143671989441,-30.034820314933942,1744061320.3746767,14.74143671989441,0.021416487838947597,1744061320.374679,14.74143671989441,-56568542383.615204,1744061320.37468,14.74143671989441,0.065,1744061320.3746812,14.74143671989441,3.1415926530576987,1744061320.3746824,14.74143671989441,30.09980976467148,1744061320.3746834,14.74143671989441,4.334372624117067e-20,1744061320.374684,14.74143671989441,8.713547017762556e-11,1744061320.3746853,14.74143671989441,0.0,1744061320.3746862,14.74143671989441,-22627416997.969524,1744061320.3746872,14.74143671989441,0.0,1744061320.3746881,14.74143671989441,28284271247.461903
+1744061320.3946583,14.761465072631836,-6.180281567285573,1744061320.39466,14.761465072631836,-30.034820314933942,1744061320.3946621,14.761465072631836,0.021416487838947597,1744061320.3946645,14.761465072631836,-56568542383.615204,1744061320.3946655,14.761465072631836,0.065,1744061320.3946664,14.761465072631836,3.1415926530576987,1744061320.3946676,14.761465072631836,30.09980976467148,1744061320.3946686,14.761465072631836,4.334372624117067e-20,1744061320.3946695,14.761465072631836,8.713547017762556e-11,1744061320.3946705,14.761465072631836,0.0,1744061320.3946717,14.761465072631836,-22627416997.969524,1744061320.3946726,14.761465072631836,0.0,1744061320.3946733,14.761465072631836,28284271247.461903
+1744061320.4147568,14.781434297561646,-6.180281567285573,1744061320.414759,14.781434297561646,-30.034820314933942,1744061320.4147613,14.781434297561646,0.021416487838947597,1744061320.4147635,14.781434297561646,-56568542383.615204,1744061320.4147646,14.781434297561646,0.065,1744061320.4147658,14.781434297561646,3.1415926530576987,1744061320.4147668,14.781434297561646,30.09980976467148,1744061320.414768,14.781434297561646,4.334372624117067e-20,1744061320.4147687,14.781434297561646,8.713547017762556e-11,1744061320.41477,14.781434297561646,0.0,1744061320.4147708,14.781434297561646,-22627416997.969524,1744061320.4147718,14.781434297561646,0.0,1744061320.4147727,14.781434297561646,28284271247.461903
+1744061320.434865,14.801435708999634,-6.180281567285573,1744061320.4348667,14.801435708999634,-30.034820314933942,1744061320.434869,14.801435708999634,0.021416487838947597,1744061320.434871,14.801435708999634,-56568542383.615204,1744061320.4348722,14.801435708999634,0.065,1744061320.4348733,14.801435708999634,3.1415926530576987,1744061320.4348743,14.801435708999634,30.09980976467148,1744061320.4348755,14.801435708999634,4.334372624117067e-20,1744061320.4348762,14.801435708999634,8.713547017762556e-11,1744061320.4348772,14.801435708999634,0.0,1744061320.434878,14.801435708999634,-22627416997.969524,1744061320.434879,14.801435708999634,0.0,1744061320.43488,14.801435708999634,28284271247.461903
+1744061320.4557884,14.82168698310852,-6.180281567285573,1744061320.4557905,14.82168698310852,-30.034820314933942,1744061320.455794,14.82168698310852,0.021416487838947597,1744061320.4557965,14.82168698310852,-56568542383.615204,1744061320.4557974,14.82168698310852,0.065,1744061320.455799,14.82168698310852,3.1415926530576987,1744061320.4558,14.82168698310852,30.09980976467148,1744061320.4558008,14.82168698310852,4.334372624117067e-20,1744061320.455802,14.82168698310852,8.713547017762556e-11,1744061320.4558032,14.82168698310852,0.0,1744061320.455804,14.82168698310852,-22627416997.969524,1744061320.4558055,14.82168698310852,0.0,1744061320.4558065,14.82168698310852,28284271247.461903
+1744061320.4746077,14.84143614768982,-6.180281567285573,1744061320.4746099,14.84143614768982,-30.034820314933942,1744061320.474612,14.84143614768982,0.021416487838947597,1744061320.4746144,14.84143614768982,-56568542383.615204,1744061320.4746153,14.84143614768982,0.065,1744061320.4746165,14.84143614768982,3.1415926530576987,1744061320.4746175,14.84143614768982,30.09980976467148,1744061320.4746187,14.84143614768982,4.334372624117067e-20,1744061320.4746194,14.84143614768982,8.713547017762556e-11,1744061320.4746206,14.84143614768982,0.0,1744061320.4746215,14.84143614768982,-22627416997.969524,1744061320.4746225,14.84143614768982,0.0,1744061320.4746232,14.84143614768982,28284271247.461903
+1744061320.494918,14.861513614654541,-6.180281567285573,1744061320.4949203,14.861513614654541,-30.034820314933942,1744061320.4949224,14.861513614654541,0.021416487838947597,1744061320.4949248,14.861513614654541,-56568542383.615204,1744061320.494926,14.861513614654541,0.065,1744061320.4949274,14.861513614654541,3.1415926530576987,1744061320.4949284,14.861513614654541,30.09980976467148,1744061320.4949293,14.861513614654541,4.334372624117067e-20,1744061320.4949305,14.861513614654541,8.713547017762556e-11,1744061320.4949315,14.861513614654541,0.0,1744061320.4949324,14.861513614654541,-22627416997.969524,1744061320.4949336,14.861513614654541,0.0,1744061320.4949343,14.861513614654541,28284271247.461903
+1744061320.5153008,14.881478309631348,-6.180281567285573,1744061320.515303,14.881478309631348,-30.034820314933942,1744061320.515305,14.881478309631348,0.021416487838947597,1744061320.5153072,14.881478309631348,-56568542383.615204,1744061320.5153084,14.881478309631348,0.065,1744061320.5153096,14.881478309631348,3.1415926530576987,1744061320.5153105,14.881478309631348,30.09980976467148,1744061320.5153117,14.881478309631348,4.334372624117067e-20,1744061320.5153127,14.881478309631348,8.713547017762556e-11,1744061320.5153136,14.881478309631348,0.0,1744061320.5153146,14.881478309631348,-22627416997.969524,1744061320.5153158,14.881478309631348,0.0,1744061320.5153165,14.881478309631348,28284271247.461903
+1744061320.5348759,14.901436805725098,-6.180281567285573,1744061320.5348778,14.901436805725098,-30.034820314933942,1744061320.5348797,14.901436805725098,0.021416487838947597,1744061320.5348818,14.901436805725098,-56568542383.615204,1744061320.5348828,14.901436805725098,0.065,1744061320.5348842,14.901436805725098,3.1415926530576987,1744061320.5348852,14.901436805725098,30.09980976467148,1744061320.534886,14.901436805725098,4.334372624117067e-20,1744061320.5348868,14.901436805725098,8.713547017762556e-11,1744061320.534888,14.901436805725098,0.0,1744061320.534889,14.901436805725098,-22627416997.969524,1744061320.53489,14.901436805725098,0.0,1744061320.5348907,14.901436805725098,28284271247.461903
+1744061320.5549874,14.92144227027893,-6.180281567285573,1744061320.5549905,14.92144227027893,-30.034820314933942,1744061320.5549934,14.92144227027893,0.021416487838947597,1744061320.5549958,14.92144227027893,-56568542383.615204,1744061320.5549972,14.92144227027893,0.065,1744061320.5549989,14.92144227027893,3.1415926530576987,1744061320.5549998,14.92144227027893,30.09980976467148,1744061320.5550008,14.92144227027893,4.334372624117067e-20,1744061320.5550022,14.92144227027893,8.713547017762556e-11,1744061320.5550034,14.92144227027893,0.0,1744061320.5550044,14.92144227027893,-22627416997.969524,1744061320.5550058,14.92144227027893,0.0,1744061320.5550067,14.92144227027893,28284271247.461903
+1744061320.5747373,14.94143795967102,-6.180281567285573,1744061320.5747395,14.94143795967102,-30.034820314933942,1744061320.5747416,14.94143795967102,0.021416487838947597,1744061320.5747437,14.94143795967102,-56568542383.615204,1744061320.574745,14.94143795967102,0.065,1744061320.5747461,14.94143795967102,3.1415926530576987,1744061320.574747,14.94143795967102,30.09980976467148,1744061320.5747483,14.94143795967102,4.334372624117067e-20,1744061320.574749,14.94143795967102,8.713547017762556e-11,1744061320.57475,14.94143795967102,0.0,1744061320.574751,14.94143795967102,-22627416997.969524,1744061320.574752,14.94143795967102,0.0,1744061320.5747528,14.94143795967102,28284271247.461903
+1744061320.5946538,14.961438179016113,-6.180281567285573,1744061320.594656,14.961438179016113,-30.034820314933942,1744061320.5946584,14.961438179016113,0.021416487838947597,1744061320.5946603,14.961438179016113,-56568542383.615204,1744061320.5946617,14.961438179016113,0.065,1744061320.5946627,14.961438179016113,3.1415926530576987,1744061320.5946639,14.961438179016113,30.09980976467148,1744061320.5946648,14.961438179016113,4.334372624117067e-20,1744061320.5946658,14.961438179016113,8.713547017762556e-11,1744061320.5946667,14.961438179016113,0.0,1744061320.5946677,14.961438179016113,-22627416997.969524,1744061320.5946689,14.961438179016113,0.0,1744061320.5946696,14.961438179016113,28284271247.461903
+1744061320.614969,14.981436491012573,-6.180281567285573,1744061320.614971,14.981436491012573,-30.034820314933942,1744061320.614973,14.981436491012573,0.021416487838947597,1744061320.6149752,14.981436491012573,-56568542383.615204,1744061320.6149762,14.981436491012573,0.065,1744061320.6149778,14.981436491012573,3.1415926530576987,1744061320.6149788,14.981436491012573,30.09980976467148,1744061320.6149797,14.981436491012573,4.334372624117067e-20,1744061320.614981,14.981436491012573,8.713547017762556e-11,1744061320.6149821,14.981436491012573,0.0,1744061320.614983,14.981436491012573,-22627416997.969524,1744061320.6149845,14.981436491012573,0.0,1744061320.6149852,14.981436491012573,28284271247.461903
+1744061320.6348698,15.001437425613403,-6.180281567285573,1744061320.6348715,15.001437425613403,-30.034820314933942,1744061320.6348736,15.001437425613403,0.021416487838947597,1744061320.6348755,15.001437425613403,-56568542383.615204,1744061320.6348767,15.001437425613403,0.065,1744061320.634878,15.001437425613403,3.1415926530576987,1744061320.6348789,15.001437425613403,30.09980976467148,1744061320.63488,15.001437425613403,4.334372624117067e-20,1744061320.634881,15.001437425613403,8.713547017762556e-11,1744061320.6348822,15.001437425613403,0.0,1744061320.6348834,15.001437425613403,-22627416997.969524,1744061320.634884,15.001437425613403,0.0,1744061320.634885,15.001437425613403,28284271247.461903
+1744061320.655575,15.021466970443726,-6.180281567285573,1744061320.6555786,15.021466970443726,-30.034820314933942,1744061320.6555827,15.021466970443726,0.021416487838947597,1744061320.6555858,15.021466970443726,-56568542383.615204,1744061320.6555874,15.021466970443726,0.065,1744061320.6555889,15.021466970443726,3.1415926530576987,1744061320.6555912,15.021466970443726,30.09980976467148,1744061320.6555924,15.021466970443726,4.334372624117067e-20,1744061320.6555939,15.021466970443726,8.713547017762556e-11,1744061320.6555963,15.021466970443726,0.0,1744061320.6555977,15.021466970443726,-22627416997.969524,1744061320.655599,15.021466970443726,0.0,1744061320.6556005,15.021466970443726,28284271247.461903
+1744061320.6747003,15.041440486907959,-6.180281567285573,1744061320.6747022,15.041440486907959,-30.034820314933942,1744061320.6747043,15.041440486907959,0.021416487838947597,1744061320.6747067,15.041440486907959,-56568542383.615204,1744061320.674708,15.041440486907959,0.065,1744061320.6747093,15.041440486907959,3.1415926530576987,1744061320.6747105,15.041440486907959,30.09980976467148,1744061320.6747115,15.041440486907959,4.334372624117067e-20,1744061320.674713,15.041440486907959,8.713547017762556e-11,1744061320.674714,15.041440486907959,0.0,1744061320.674715,15.041440486907959,-22627416997.969524,1744061320.6747162,15.041440486907959,0.0,1744061320.6747172,15.041440486907959,28284271247.461903
+1744061320.6946826,15.061438798904419,-6.180281567285573,1744061320.6946845,15.061438798904419,-30.034820314933942,1744061320.6946867,15.061438798904419,0.021416487838947597,1744061320.6946888,15.061438798904419,-56568542383.615204,1744061320.6946898,15.061438798904419,0.065,1744061320.6946912,15.061438798904419,3.1415926530576987,1744061320.6946924,15.061438798904419,30.09980976467148,1744061320.694693,15.061438798904419,4.334372624117067e-20,1744061320.6946945,15.061438798904419,8.713547017762556e-11,1744061320.6946955,15.061438798904419,0.0,1744061320.6946964,15.061438798904419,-22627416997.969524,1744061320.6946976,15.061438798904419,0.0,1744061320.6946988,15.061438798904419,28284271247.461903
+1744061320.7147064,15.081459045410156,-6.180281567285573,1744061320.7147086,15.081459045410156,-30.034820314933942,1744061320.7147105,15.081459045410156,0.021416487838947597,1744061320.7147129,15.081459045410156,-56568542383.615204,1744061320.7147138,15.081459045410156,0.065,1744061320.7147152,15.081459045410156,3.1415926530576987,1744061320.7147164,15.081459045410156,30.09980976467148,1744061320.7147171,15.081459045410156,4.334372624117067e-20,1744061320.714718,15.081459045410156,8.713547017762556e-11,1744061320.7147193,15.081459045410156,0.0,1744061320.7147202,15.081459045410156,-22627416997.969524,1744061320.7147212,15.081459045410156,0.0,1744061320.7147224,15.081459045410156,28284271247.461903
+1744061320.7353501,15.101440906524658,-6.180281567285573,1744061320.735352,15.101440906524658,-30.034820314933942,1744061320.7353544,15.101440906524658,0.021416487838947597,1744061320.7353563,15.101440906524658,-56568542383.615204,1744061320.7353578,15.101440906524658,0.065,1744061320.735359,15.101440906524658,3.1415926530576987,1744061320.73536,15.101440906524658,30.09980976467148,1744061320.7353609,15.101440906524658,4.334372624117067e-20,1744061320.7353618,15.101440906524658,8.713547017762556e-11,1744061320.735363,15.101440906524658,0.0,1744061320.7353637,15.101440906524658,-22627416997.969524,1744061320.7353652,15.101440906524658,0.0,1744061320.735366,15.101440906524658,28284271247.461903
+1744061320.755067,15.121459007263184,-6.180281567285573,1744061320.7550688,15.121459007263184,-30.034820314933942,1744061320.7550714,15.121459007263184,0.021416487838947597,1744061320.7550738,15.121459007263184,-56568542383.615204,1744061320.755075,15.121459007263184,0.065,1744061320.7550764,15.121459007263184,3.1415926530576987,1744061320.7550776,15.121459007263184,30.09980976467148,1744061320.7550786,15.121459007263184,4.334372624117067e-20,1744061320.7550797,15.121459007263184,8.713547017762556e-11,1744061320.7550807,15.121459007263184,0.0,1744061320.7550817,15.121459007263184,-22627416997.969524,1744061320.7550828,15.121459007263184,0.0,1744061320.755084,15.121459007263184,28284271247.461903
+1744061320.7747793,15.14146637916565,-6.180281567285573,1744061320.7747812,15.14146637916565,-30.034820314933942,1744061320.7747834,15.14146637916565,0.021416487838947597,1744061320.7747855,15.14146637916565,-56568542383.615204,1744061320.7747867,15.14146637916565,0.065,1744061320.7747881,15.14146637916565,3.1415926530576987,1744061320.774789,15.14146637916565,30.09980976467148,1744061320.7747898,15.14146637916565,4.334372624117067e-20,1744061320.774791,15.14146637916565,8.713547017762556e-11,1744061320.774792,15.14146637916565,0.0,1744061320.774793,15.14146637916565,-22627416997.969524,1744061320.774794,15.14146637916565,0.0,1744061320.774795,15.14146637916565,28284271247.461903
+1744061320.7947793,15.161444902420044,-6.180281567285573,1744061320.7947817,15.161444902420044,-30.034820314933942,1744061320.7947843,15.161444902420044,0.021416487838947597,1744061320.7947862,15.161444902420044,-56568542383.615204,1744061320.7947874,15.161444902420044,0.065,1744061320.7947886,15.161444902420044,3.1415926530576987,1744061320.7947898,15.161444902420044,30.09980976467148,1744061320.794791,15.161444902420044,4.334372624117067e-20,1744061320.794792,15.161444902420044,8.713547017762556e-11,1744061320.7947931,15.161444902420044,0.0,1744061320.794794,15.161444902420044,-22627416997.969524,1744061320.794795,15.161444902420044,0.0,1744061320.794796,15.161444902420044,28284271247.461903
+1744061320.8146718,15.1814706325531,-6.180281567285573,1744061320.814674,15.1814706325531,-30.034820314933942,1744061320.814676,15.1814706325531,0.021416487838947597,1744061320.8146782,15.1814706325531,-56568542383.615204,1744061320.8146794,15.1814706325531,0.065,1744061320.8146806,15.1814706325531,3.1415926530576987,1744061320.8146815,15.1814706325531,30.09980976467148,1744061320.8146827,15.1814706325531,4.334372624117067e-20,1744061320.8146837,15.1814706325531,8.713547017762556e-11,1744061320.8146849,15.1814706325531,0.0,1744061320.814686,15.1814706325531,-22627416997.969524,1744061320.814687,15.1814706325531,0.0,1744061320.8146877,15.1814706325531,28284271247.461903
+1744061320.835444,15.201592206954956,-6.239702609678414,1744061320.8354464,15.201592206954956,-29.97903575034436,1744061320.835449,15.201592206954956,0.021416487838947597,1744061320.8354514,15.201592206954956,-56568542383.615204,1744061320.8354526,15.201592206954956,0.065,1744061320.835454,15.201592206954956,3.1415926530586846,1744061320.8354552,15.201592206954956,30.044040080623308,1744061320.8354568,15.201592206954956,4.32634178958986e-20,1744061320.8354578,15.201592206954956,9.11111129681357e-11,1744061320.835459,15.201592206954956,0.0,1744061320.8354604,15.201592206954956,-22627416997.969524,1744061320.8354616,15.201592206954956,0.0,1744061320.8354626,15.201592206954956,28284271247.461903
+1744061320.8547072,15.221444368362427,-6.239702609678414,1744061320.854709,15.221444368362427,-29.97903575034436,1744061320.8547115,15.221444368362427,0.021416487838947597,1744061320.854714,15.221444368362427,-56568542383.615204,1744061320.8547149,15.221444368362427,0.065,1744061320.854716,15.221444368362427,3.1415926530586846,1744061320.8547173,15.221444368362427,30.044040080623308,1744061320.8547182,15.221444368362427,4.32634178958986e-20,1744061320.8547192,15.221444368362427,9.11111129681357e-11,1744061320.8547206,15.221444368362427,0.0,1744061320.8547213,15.221444368362427,-22627416997.969524,1744061320.8547223,15.221444368362427,0.0,1744061320.8547232,15.221444368362427,28284271247.461903
+1744061320.874914,15.241438150405884,-6.239702609678414,1744061320.8749158,15.241438150405884,-29.97903575034436,1744061320.8749182,15.241438150405884,0.021416487838947597,1744061320.8749204,15.241438150405884,-56568542383.615204,1744061320.8749216,15.241438150405884,0.065,1744061320.874923,15.241438150405884,3.1415926530586846,1744061320.874924,15.241438150405884,30.044040080623308,1744061320.8749251,15.241438150405884,4.32634178958986e-20,1744061320.8749259,15.241438150405884,9.11111129681357e-11,1744061320.8749268,15.241438150405884,0.0,1744061320.8749278,15.241438150405884,-22627416997.969524,1744061320.874929,15.241438150405884,0.0,1744061320.8749297,15.241438150405884,28284271247.461903
+1744061320.8951058,15.261558055877686,-6.239702609678414,1744061320.8951085,15.261558055877686,-29.97903575034436,1744061320.8951106,15.261558055877686,0.021416487838947597,1744061320.8951132,15.261558055877686,-56568542383.615204,1744061320.8951144,15.261558055877686,0.065,1744061320.895116,15.261558055877686,3.1415926530586846,1744061320.8951173,15.261558055877686,30.044040080623308,1744061320.895118,15.261558055877686,4.32634178958986e-20,1744061320.89512,15.261558055877686,9.11111129681357e-11,1744061320.8951213,15.261558055877686,0.0,1744061320.8951228,15.261558055877686,-22627416997.969524,1744061320.8951237,15.261558055877686,0.0,1744061320.8951254,15.261558055877686,28284271247.461903
+1744061320.9152007,15.281503438949585,-6.239702609678414,1744061320.9152029,15.281503438949585,-29.97903575034436,1744061320.915205,15.281503438949585,0.021416487838947597,1744061320.9152076,15.281503438949585,-56568542383.615204,1744061320.9152088,15.281503438949585,0.065,1744061320.91521,15.281503438949585,3.1415926530586846,1744061320.915211,15.281503438949585,30.044040080623308,1744061320.915212,15.281503438949585,4.32634178958986e-20,1744061320.9152129,15.281503438949585,9.11111129681357e-11,1744061320.915214,15.281503438949585,0.0,1744061320.915215,15.281503438949585,-22627416997.969524,1744061320.9152162,15.281503438949585,0.0,1744061320.915217,15.281503438949585,28284271247.461903
+1744061320.9354281,15.301464319229126,-6.239702609678414,1744061320.9354298,15.301464319229126,-29.97903575034436,1744061320.9354324,15.301464319229126,0.021416487838947597,1744061320.9354348,15.301464319229126,-56568542383.615204,1744061320.9354358,15.301464319229126,0.065,1744061320.935457,15.301464319229126,3.1415926530586846,1744061320.9354584,15.301464319229126,30.044040080623308,1744061320.9354591,15.301464319229126,4.32634178958986e-20,1744061320.93546,15.301464319229126,9.11111129681357e-11,1744061320.935461,15.301464319229126,0.0,1744061320.9354622,15.301464319229126,-22627416997.969524,1744061320.9354632,15.301464319229126,0.0,1744061320.9354641,15.301464319229126,28284271247.461903
+1744061320.954971,15.32150912284851,-6.239702609678414,1744061320.9549732,15.32150912284851,-29.97903575034436,1744061320.9549758,15.32150912284851,0.021416487838947597,1744061320.954978,15.32150912284851,-56568542383.615204,1744061320.9549794,15.32150912284851,0.065,1744061320.9549806,15.32150912284851,3.1415926530586846,1744061320.9549818,15.32150912284851,30.044040080623308,1744061320.954983,15.32150912284851,4.32634178958986e-20,1744061320.954984,15.32150912284851,9.11111129681357e-11,1744061320.9549854,15.32150912284851,0.0,1744061320.9549866,15.32150912284851,-22627416997.969524,1744061320.9549875,15.32150912284851,0.0,1744061320.9549885,15.32150912284851,28284271247.461903
+1744061320.9746866,15.341437101364136,-6.239702609678414,1744061320.9746885,15.341437101364136,-29.97903575034436,1744061320.9746912,15.341437101364136,0.021416487838947597,1744061320.9746933,15.341437101364136,-56568542383.615204,1744061320.9746947,15.341437101364136,0.065,1744061320.974696,15.341437101364136,3.1415926530586846,1744061320.974697,15.341437101364136,30.044040080623308,1744061320.974698,15.341437101364136,4.32634178958986e-20,1744061320.974699,15.341437101364136,9.11111129681357e-11,1744061320.9747,15.341437101364136,0.0,1744061320.9747012,15.341437101364136,-22627416997.969524,1744061320.9747021,15.341437101364136,0.0,1744061320.9747028,15.341437101364136,28284271247.461903
+1744061320.9950864,15.361493110656738,-6.239702609678414,1744061320.9950888,15.361493110656738,-29.97903575034436,1744061320.9950914,15.361493110656738,0.021416487838947597,1744061320.9950938,15.361493110656738,-56568542383.615204,1744061320.9950948,15.361493110656738,0.065,1744061320.995096,15.361493110656738,3.1415926530586846,1744061320.9950974,15.361493110656738,30.044040080623308,1744061320.995098,15.361493110656738,4.32634178958986e-20,1744061320.995099,15.361493110656738,9.11111129681357e-11,1744061320.9951003,15.361493110656738,0.0,1744061320.9951012,15.361493110656738,-22627416997.969524,1744061320.9951024,15.361493110656738,0.0,1744061320.9951036,15.361493110656738,28284271247.461903
+1744061321.0146534,15.38146424293518,-6.239702609678414,1744061321.014655,15.38146424293518,-29.97903575034436,1744061321.0146575,15.38146424293518,0.021416487838947597,1744061321.01466,15.38146424293518,-56568542383.615204,1744061321.0146608,15.38146424293518,0.065,1744061321.014662,15.38146424293518,3.1415926530586846,1744061321.0146632,15.38146424293518,30.044040080623308,1744061321.014664,15.38146424293518,4.32634178958986e-20,1744061321.014665,15.38146424293518,9.11111129681357e-11,1744061321.0146663,15.38146424293518,0.0,1744061321.014667,15.38146424293518,-22627416997.969524,1744061321.014668,15.38146424293518,0.0,1744061321.014669,15.38146424293518,28284271247.461903
+1744061321.0351667,15.40148377418518,-6.239702609678414,1744061321.035169,15.40148377418518,-29.97903575034436,1744061321.0351708,15.40148377418518,0.021416487838947597,1744061321.035173,15.40148377418518,-56568542383.615204,1744061321.0351741,15.40148377418518,0.065,1744061321.0351753,15.40148377418518,3.1415926530586846,1744061321.0351765,15.40148377418518,30.044040080623308,1744061321.0351772,15.40148377418518,4.32634178958986e-20,1744061321.0351782,15.40148377418518,9.11111129681357e-11,1744061321.0351796,15.40148377418518,0.0,1744061321.0351803,15.40148377418518,-22627416997.969524,1744061321.0351813,15.40148377418518,0.0,1744061321.0351822,15.40148377418518,28284271247.461903
diff --git a/testing/racing_logs/launch_control_2/behavior.json b/testing/racing_logs/launch_control_2/behavior.json
new file mode 100644
index 000000000..a35749fbe
--- /dev/null
+++ b/testing/racing_logs/launch_control_2/behavior.json
@@ -0,0 +1,922 @@
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061305.6337068, "x": -88.23521476423988, "y": 40.09283952838941, "z": 203.0753218697915, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061305.6323853}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.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": 1744061305.6323853}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061305.733896, "x": -88.23521476423988, "y": 40.09283952838941, "z": 203.0753218697915, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061305.7337751}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.0380206849704777e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061305.7337751}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.0380206849704777e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061305.7538643}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.0380206849704777e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061305.7738447}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.0380206849704777e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061305.79388}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.0380206849704777e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061305.8138704}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061305.8339686, "x": -88.2352146978726, "y": 40.09283937377724, "z": 203.0870693331494, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061305.8338478}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.0380206849704777e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061305.8338478}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.0553502853391863e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061305.8538852}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.0553502853391863e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061305.8738365}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.0553502853391863e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061305.8938715}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.0553502853391863e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061305.9138355}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061305.9339647, "x": -88.2352146978726, "y": 40.09283937377724, "z": 203.0870693331494, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061305.9338439}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.0553502853391863e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061305.9338439}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.0553502853391863e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061305.9539044}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.0553502853391863e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061305.9738388}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.0553502853391863e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061305.994187}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.0553502853391863e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.0138443}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061306.034322, "x": -88.2352146978726, "y": 40.09283937377724, "z": 203.0870693331494, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061306.0338726}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.0553502853391863e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.0338726}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.0553502853391863e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.0538476}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.0553502853391863e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.0738602}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.0553502853391863e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.0938935}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.0553502853391863e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.1138384}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061306.1339304, "x": -88.2352146978726, "y": 40.09283937377724, "z": 203.0870693331494, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061306.1338356}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.0553502853391863e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.1338356}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.0553502853391863e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.153852}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.0553502853391863e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.173842}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.0553502853391863e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.1939049}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.0553502853391863e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.2138443}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061306.23392, "x": -88.2352146978726, "y": 40.09283937377724, "z": 203.0870693331494, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061306.2338333}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.0553502853391863e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.2338333}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.0553502853391863e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.2538705}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.0553502853391863e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.2738562}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.0553502853391863e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.2938704}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.0553502853391863e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.313838}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061306.3339314, "x": -88.23521463594511, "y": 40.09283924408874, "z": 203.09491651486164, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061306.333837}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.0553502853391863e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.333837}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.0553502853391863e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.353911}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.054562576230224e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.3741548}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.054562576230224e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.3938704}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.054562576230224e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.413857}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061306.4339495, "x": -88.23521463594511, "y": 40.09283924408874, "z": 203.09491651486164, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061306.433849}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.054562576230224e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.433849}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.054562576230224e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.4538457}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.054562576230224e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.473837}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.054562576230224e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.4938803}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.054562576230224e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.5138512}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061306.5342715, "x": -88.23521463594511, "y": 40.09283924408874, "z": 203.09491651486164, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061306.533869}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.054562576230224e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.533869}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.054562576230224e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.5539196}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.054562576230224e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.5738673}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.054562576230224e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.5938838}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.054562576230224e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.6138678}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061306.633974, "x": -88.23521463594511, "y": 40.09283924408874, "z": 203.09491651486164, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061306.6338453}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.054562576230224e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.6338453}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.054562576230224e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.653877}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.054562576230224e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.6738808}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.054562576230224e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.69387}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.054562576230224e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.7138796}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061306.7339482, "x": -88.23521463594511, "y": 40.09283924408874, "z": 203.09491651486164, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061306.7338395}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.054562576230224e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.7338395}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.054562576230224e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.7538412}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.054562576230224e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.7738767}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.054562576230224e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.79386}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.054562576230224e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.8138342}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061306.834036, "x": -88.23521460457192, "y": 40.09283917419233, "z": 203.11125407440912, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061306.8338876}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.054562576230224e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.8338876}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.054562576230224e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.8538916}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.054562576230224e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.873864}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.054562576230224e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.893865}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.058501121768429e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.9138596}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061306.933923, "x": -88.23521460457192, "y": 40.09283917419233, "z": 203.11125407440912, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061306.9338355}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.058501121768429e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.9338355}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.058501121768429e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.9539125}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.058501121768429e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.9738405}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.058501121768429e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061306.993846}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.058501121768429e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.013835}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061307.0339499, "x": -88.23521460457192, "y": 40.09283917419233, "z": 203.11125407440912, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061307.0338633}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.058501121768429e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.0338633}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.058501121768429e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.0538876}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.058501121768429e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.0738654}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.058501121768429e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.093867}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.058501121768429e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.1138878}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061307.1339703, "x": -88.23521460457192, "y": 40.09283917419233, "z": 203.11125407440912, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061307.1338763}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.058501121768429e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.1338763}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.058501121768429e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.153897}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.058501121768429e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.173847}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.058501121768429e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.1938841}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.058501121768429e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.2138622}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061307.2346816, "x": -88.23521460457192, "y": 40.09283917419233, "z": 203.11125407440912, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061307.2339551}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.058501121768429e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.2339551}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.058501121768429e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.2539349}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.058501121768429e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.2738426}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.058501121768429e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.2938812}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.058501121768429e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.3138394}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061307.333968, "x": -88.23521457070946, "y": 40.09283903996271, "z": 203.1177472247585, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061307.333842}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.058501121768429e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.333842}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.133333486999471e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.3538482}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.133333486999471e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.3738856}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.133333486999471e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.393879}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.133333486999471e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.4138653}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061307.4342809, "x": -88.23521457070946, "y": 40.09283903996271, "z": 203.1177472247585, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061307.4338887}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.133333486999471e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.4338887}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.133333486999471e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.4538474}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.133333486999471e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.4738357}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.133333486999471e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.493881}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.133333486999471e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.5138643}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061307.5340364, "x": -88.23521457070946, "y": 40.09283903996271, "z": 203.1177472247585, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061307.5338795}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.133333486999471e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.5338795}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.133333486999471e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.5539067}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.133333486999471e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.573902}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.133333486999471e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.5938356}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.133333486999471e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.6138685}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061307.6342585, "x": -88.23521457070946, "y": 40.09283903996271, "z": 203.1177472247585, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061307.6339138}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.133333486999471e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.6339138}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.133333486999471e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.653882}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.133333486999471e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.6738503}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.133333486999471e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.6939225}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.133333486999471e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.7138677}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061307.733925, "x": -88.23521457070946, "y": 40.09283903996271, "z": 203.1177472247585, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061307.7338343}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.133333486999471e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.7338343}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.133333486999471e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.7538836}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.133333486999471e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.7738516}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.133333486999471e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.793872}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.133333486999471e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.8138814}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061307.833954, "x": -88.23521457201167, "y": 40.09283905827421, "z": 203.12314031121383, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061307.8338625}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.133333486999471e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.8338625}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.133333486999471e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.8538818}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.133333486999471e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.8738396}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1152161775224225e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.8938754}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1152161775224225e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.9138343}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061307.9344952, "x": -88.23521457201167, "y": 40.09283905827421, "z": 203.12314031121383, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061307.9338841}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1152161775224225e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.9338841}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1152161775224225e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.953883}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1152161775224225e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.9738638}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1152161775224225e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061307.9938676}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1152161775224225e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.0138316}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061308.0339782, "x": -88.23521457201167, "y": 40.09283905827421, "z": 203.12314031121383, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061308.033836}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1152161775224225e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.033836}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1152161775224225e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.053907}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1152161775224225e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.0738678}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1152161775224225e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.0938509}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1152161775224225e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.1138482}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061308.1342719, "x": -88.23521457201167, "y": 40.09283905827421, "z": 203.12314031121383, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061308.133885}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1152161775224225e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.133885}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1152161775224225e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.1538577}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1152161775224225e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.1738849}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1152161775224225e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.1938782}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1152161775224225e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.2138648}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061308.2340403, "x": -88.23521457201167, "y": 40.09283905827421, "z": 203.12314031121383, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061308.2338731}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1152161775224225e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.2338731}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1152161775224225e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.2538366}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1152161775224225e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.2738795}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1152161775224225e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.293838}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1152161775224225e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.3139036}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061308.334009, "x": -88.23521461434048, "y": 40.09283896868358, "z": 203.12158853835624, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061308.3338487}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.327897636601356e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.3338487}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.327897636601356e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.3538737}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.327897636601356e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.373918}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.327897636601356e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.3938358}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.327897636601356e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.4138656}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061308.4340346, "x": -88.23521461434048, "y": 40.09283896868358, "z": 203.12158853835624, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061308.4338572}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.327897636601356e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.4338572}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.327897636601356e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.4538727}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.327897636601356e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.473868}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.327897636601356e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.4938436}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.327897636601356e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.5138733}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061308.533927, "x": -88.23521461434048, "y": 40.09283896868358, "z": 203.12158853835624, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061308.5338347}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.327897636601356e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.5338347}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.327897636601356e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.5538573}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.327897636601356e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.5738578}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.327897636601356e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.59386}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.327897636601356e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.6139207}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061308.6339943, "x": -88.23521461434048, "y": 40.09283896868358, "z": 203.12158853835624, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061308.633894}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.327897636601356e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.633894}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.327897636601356e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.6538563}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.327897636601356e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.6738706}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.327897636601356e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.693864}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.327897636601356e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.7138698}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061308.7339432, "x": -88.23521461434048, "y": 40.09283896868358, "z": 203.12158853835624, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061308.733856}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.327897636601356e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.733856}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.327897636601356e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.7539196}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.327897636601356e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.7738802}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.327897636601356e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.793841}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.327897636601356e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.8144314}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061308.833934, "x": -88.23521456512684, "y": 40.092838906551705, "z": 203.1118039196392, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061308.8338394}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.327897636601356e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.8338394}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.327897636601356e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.8538969}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.327897636601356e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.8738346}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.278271962815878e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.8938322}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.278271962815878e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.913873}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061308.933951, "x": -88.23521456512684, "y": 40.092838906551705, "z": 203.1118039196392, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061308.93384}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.278271962815878e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.93384}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.278271962815878e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.953846}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.278271962815878e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.9738646}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.278271962815878e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061308.9938388}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.278271962815878e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.0138657}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061309.0339983, "x": -88.23521456512684, "y": 40.092838906551705, "z": 203.1118039196392, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061309.0338788}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.278271962815878e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.0338788}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.278271962815878e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.0538445}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.278271962815878e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.073865}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.278271962815878e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.093879}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.278271962815878e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.1138308}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061309.1339328, "x": -88.23521456512684, "y": 40.092838906551705, "z": 203.1118039196392, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061309.1338365}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.278271962815878e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.1338365}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.278271962815878e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.1538312}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.278271962815878e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.1738648}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.278271962815878e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.1939137}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.278271962815878e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.2138717}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061309.2340798, "x": -88.23521456512684, "y": 40.092838906551705, "z": 203.1118039196392, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061309.233854}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.278271962815878e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.233854}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.278271962815878e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.2538426}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.278271962815878e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.2738655}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.278271962815878e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.293881}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.278271962815878e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.3138418}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061309.3339212, "x": -88.23521462469802, "y": 40.09283884978715, "z": 203.09406439150115, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061309.333832}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.278271962815878e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.333832}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.4956796765411068e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.3538954}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.4956796765411068e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.3738778}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.4956796765411068e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.3938386}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.4956796765411068e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.4138923}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061309.4339237, "x": -88.23521462469802, "y": 40.09283884978715, "z": 203.09406439150115, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061309.4338317}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.4956796765411068e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.4338317}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.4956796765411068e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.453853}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.4956796765411068e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.4738405}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.4956796765411068e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.4939816}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.4956796765411068e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.5138764}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061309.5339518, "x": -88.23521462469802, "y": 40.09283884978715, "z": 203.09406439150115, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061309.533862}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.4956796765411068e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.533862}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.4956796765411068e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.5538564}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.4956796765411068e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.5738568}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.4956796765411068e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.593841}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.4956796765411068e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.6138473}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061309.6339796, "x": -88.23521462469802, "y": 40.09283884978715, "z": 203.09406439150115, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061309.6338692}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.4956796765411068e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.6338692}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.4956796765411068e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.6538846}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.4956796765411068e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.6738315}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.4956796765411068e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.6938725}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.4956796765411068e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.7138715}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061309.7343013, "x": -88.23521462469802, "y": 40.09283884978715, "z": 203.09406439150115, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061309.7339034}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.4956796765411068e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.7339034}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.4956796765411068e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.7538526}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.4956796765411068e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.7738793}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.4956796765411068e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.7939146}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.4956796765411068e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.8138635}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061309.8340487, "x": -88.23521471261054, "y": 40.09283884844169, "z": 203.07504468395467, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061309.8338878}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.4956796765411068e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.8338878}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.4956796765411068e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.8538356}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.4956796765411068e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.873839}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.4956796765411068e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.893866}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.717813644912332e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.913842}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061309.934216, "x": -88.23521471261054, "y": 40.09283884844169, "z": 203.07504468395467, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061309.9338906}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.717813644912332e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.9338906}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.717813644912332e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.9538522}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.717813644912332e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.973869}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.717813644912332e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061309.9938614}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.717813644912332e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.0138688}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061310.034, "x": -88.23521471261054, "y": 40.09283884844169, "z": 203.07504468395467, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061310.0338507}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.717813644912332e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.0338507}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.717813644912332e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.0538747}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.717813644912332e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.0738645}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.717813644912332e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.0938666}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.717813644912332e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.1138613}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061310.1339533, "x": -88.23521471261054, "y": 40.09283884844169, "z": 203.07504468395467, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061310.1338387}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.717813644912332e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.1338387}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.717813644912332e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.1538615}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.717813644912332e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.173833}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.717813644912332e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.193873}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.717813644912332e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.2138736}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061310.2339678, "x": -88.23521471261054, "y": 40.09283884844169, "z": 203.07504468395467, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061310.233875}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.717813644912332e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.233875}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.717813644912332e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.2538598}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.717813644912332e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.2738404}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.717813644912332e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.293863}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.717813644912332e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.3137982}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061310.333924, "x": -88.23521482663227, "y": 40.09283886174038, "z": 203.04728469525614, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061310.3338325}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.988785577961596e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.3338325}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.988785577961596e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.3538368}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.988785577961596e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.3738337}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.988785577961596e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.393956}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.988785577961596e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.413869}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061310.4340112, "x": -88.23521482663227, "y": 40.09283886174038, "z": 203.04728469525614, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061310.4338608}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.988785577961596e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.4338608}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.988785577961596e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.4538355}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.988785577961596e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.4738367}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.988785577961596e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.493842}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.988785577961596e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.5138576}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061310.5339942, "x": -88.23521482663227, "y": 40.09283886174038, "z": 203.04728469525614, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061310.533881}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.988785577961596e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.533881}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.988785577961596e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.5538583}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.988785577961596e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.5738382}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.988785577961596e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.5938427}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.988785577961596e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.6138625}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061310.6339598, "x": -88.23521482663227, "y": 40.09283886174038, "z": 203.04728469525614, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061310.6338382}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.988785577961596e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.6338382}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.988785577961596e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.6538649}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.988785577961596e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.6738362}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.988785577961596e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.6938472}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.988785577961596e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.7138321}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061310.7340014, "x": -88.23521482663227, "y": 40.09283886174038, "z": 203.04728469525614, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061310.733863}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.988785577961596e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.733863}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.988785577961596e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.7538366}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.988785577961596e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.7738316}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.988785577961596e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.7938333}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.988785577961596e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.8138566}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061310.8339777, "x": -88.23521493948475, "y": 40.0928388800974, "z": 203.02170893589732, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061310.8338656}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.988785577961596e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.8338656}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2503050017201786e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.8538678}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2503050017201786e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.8738322}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2503050017201786e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.8938754}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2503050017201786e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.9138775}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061310.9339569, "x": -88.23521493948475, "y": 40.0928388800974, "z": 203.02170893589732, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061310.9338307}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2503050017201786e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.9338307}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2503050017201786e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.9538572}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2503050017201786e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.9738317}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2503050017201786e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061310.9938655}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2503050017201786e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061311.0138388}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061311.0339212, "x": -88.23521493948475, "y": 40.0928388800974, "z": 203.02170893589732, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061311.0338302}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2503050017201786e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061311.0338302}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2503050017201786e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061311.0539207}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2503050017201786e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061311.0738742}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2503050017201786e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061311.0938356}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2503050017201786e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061311.1138325}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061311.133988, "x": -88.23521493948475, "y": 40.0928388800974, "z": 203.02170893589732, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061311.13386}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2503050017201786e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061311.13386}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2503050017201786e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061311.153875}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2503050017201786e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061311.1738544}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2503050017201786e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061311.1938562}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2503050017201786e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061311.2138948}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061311.2339375, "x": -88.23521493948475, "y": 40.0928388800974, "z": 203.02170893589732, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061311.233837}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2503050017201786e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061311.233837}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2503050017201786e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061311.2538826}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2503050017201786e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061311.273869}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2503050017201786e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061311.29383}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2503050017201786e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061311.3138742}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061311.3340647, "x": -88.2352150019191, "y": 40.09283891019647, "z": 202.9936259110962, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061311.3338811}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2503050017201786e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061311.3338811}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2503050017201786e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061311.3538797}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2503050017201786e-21, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061311.373867}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.3716122043064546e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.02, "gear": 0, "accelerator_pedal_position": 0.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": 1744061311.393897}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.3716122043064546e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.02, "gear": 0, "accelerator_pedal_position": 0.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": 1744061311.4138403}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061311.433967, "x": -88.2352150019191, "y": 40.09283891019647, "z": 202.9936259110962, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5597988162215617, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061311.4338655}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.3716122043064546e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.09, "gear": 0, "accelerator_pedal_position": 0.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": 1744061311.4338655}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.3716122043064546e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.09, "gear": 0, "accelerator_pedal_position": 0.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": 1744061311.453858}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.3716122043064546e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.19, "gear": 0, "accelerator_pedal_position": 0.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": 1744061311.4738362}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.3716122043064546e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.25, "gear": 0, "accelerator_pedal_position": 0.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": 1744061311.493844}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.3716122043064546e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.25, "gear": 0, "accelerator_pedal_position": 0.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": 1744061311.513859}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061311.5340607, "x": -88.2352150019191, "y": 40.09283891019647, "z": 202.9936259110962, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5656178162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061311.5338457}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.3716122043064546e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2, "gear": 0, "accelerator_pedal_position": 0.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": 1744061311.5338457}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.3716122043064546e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2, "gear": 0, "accelerator_pedal_position": 0.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": 1744061311.5538716}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.3716122043064546e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.06, "gear": 0, "accelerator_pedal_position": 0.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": 1744061311.5739024}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.3716122043064546e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.1, "gear": 0, "accelerator_pedal_position": 0.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": 1744061311.5938447}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.3716122043064546e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.1, "gear": 0, "accelerator_pedal_position": 0.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": 1744061311.613869}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061311.634003, "x": -88.2352150019191, "y": 40.09283891019647, "z": 202.9936259110962, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5582538162215616, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061311.6338727}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.3716122043064546e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.06, "gear": 0, "accelerator_pedal_position": 0.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": 1744061311.6338727}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.3716122043064546e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.06, "gear": 0, "accelerator_pedal_position": 0.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": 1744061311.6538568}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.3716122043064546e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.24, "gear": 0, "accelerator_pedal_position": 0.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": 1744061311.673868}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.3716122043064546e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.27, "gear": 0, "accelerator_pedal_position": 0.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": 1744061311.6938672}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.3716122043064546e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.27, "gear": 0, "accelerator_pedal_position": 0.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": 1744061311.7138662}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061311.7339706, "x": -88.2352150019191, "y": 40.09283891019647, "z": 202.9936259110962, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5672468162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061311.7338674}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.3716122043064546e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.23, "gear": 0, "accelerator_pedal_position": 0.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": 1744061311.7338674}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.3716122043064546e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.23, "gear": 0, "accelerator_pedal_position": 0.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": 1744061311.7538579}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.3716122043064546e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.16, "gear": 0, "accelerator_pedal_position": 0.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": 1744061311.7738366}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.3716122043064546e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.26, "gear": 0, "accelerator_pedal_position": 0.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": 1744061311.7938645}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.3716122043064546e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.26, "gear": 0, "accelerator_pedal_position": 0.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": 1744061311.81383}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061311.833915, "x": -88.23521531009726, "y": 40.09283897444407, "z": 202.977514726211, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5733738162215616, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061311.8338318}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.3716122043064546e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.34, "gear": 0, "accelerator_pedal_position": 0.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": 1744061311.8338318}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.069522473730866e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.34, "gear": 0, "accelerator_pedal_position": 0.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": 1744061311.853845}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.069522473730866e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.56, "gear": 0, "accelerator_pedal_position": 0.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": 1744061311.8738332}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.069522473730866e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.56, "gear": 0, "accelerator_pedal_position": 0.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": 1744061311.8938463}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.069522473730866e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.56, "gear": 0, "accelerator_pedal_position": 0.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": 1744061311.9138691}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061311.9339497, "x": -88.23521531009726, "y": 40.09283897444407, "z": 202.977514726211, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5791538162215617, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061311.9338598}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.069522473730866e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.44, "gear": 0, "accelerator_pedal_position": 0.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": 1744061311.9338598}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.069522473730866e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.44, "gear": 0, "accelerator_pedal_position": 0.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": 1744061311.9538743}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.069522473730866e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.24, "gear": 0, "accelerator_pedal_position": 0.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": 1744061311.9738357}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.069522473730866e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5, "gear": 0, "accelerator_pedal_position": 0.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": 1744061311.993869}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.069522473730866e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.0138333}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061312.0339465, "x": -88.23521531009726, "y": 40.09283897444407, "z": 202.977514726211, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5944788162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061312.0338337}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.069522473730866e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.69, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.0338337}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.069522473730866e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.69, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.0538757}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.069522473730866e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.93, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.0738328}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.069522473730866e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.74, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.0939095}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.069522473730866e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.74, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.1138313}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061312.133954, "x": -88.23521531009726, "y": 40.09283897444407, "z": 202.977514726211, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5875818162215616, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061312.133837}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.069522473730866e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.58, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.133837}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.069522473730866e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.58, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.1538422}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.069522473730866e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.1738508}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.069522473730866e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.99, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.1939557}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.069522473730866e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.99, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.213828}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061312.2339675, "x": -88.23521531009726, "y": 40.09283897444407, "z": 202.977514726211, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6259428162215617, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061312.2338653}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.069522473730866e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.15, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.2338653}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.069522473730866e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.15, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.2538714}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.069522473730866e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.18, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.273856}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.069522473730866e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.05, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.2938292}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.069522473730866e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.05, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.3138652}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061312.3342485, "x": -88.23521887554999, "y": 40.092838776991435, "z": 201.33673591258997, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6194538162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061312.3338993}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.069522473730866e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.06, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.3338993}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.069522473730866e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.06, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.353864}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.069522473730866e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.26, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.3738604}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.069522473730866e-21, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.3938296}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3263663178842098e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.41386}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061312.4339907, "x": -88.23521887554999, "y": 40.09283877699143, "z": 202.96236688363427, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6527178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061312.4338756}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3263663178842098e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.4338756}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3263663178842098e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.4538412}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3263663178842098e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.42, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.4738302}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3263663178842098e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.42, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.4938784}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3263663178842098e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.5138588}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061312.5339544, "x": -88.23521887554999, "y": 40.09283877699143, "z": 202.96236688363427, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6616388162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061312.5338619}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3263663178842098e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.61, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.5338619}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3263663178842098e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.61, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.553843}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3263663178842098e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.84, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.5738313}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3263663178842098e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.84, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.5938408}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3263663178842098e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.81, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.613877}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061312.6339238, "x": -88.23521887554999, "y": 40.09283877699143, "z": 202.96236688363427, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6784788162215616, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061312.6338289}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3263663178842098e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.81, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.6338289}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3263663178842098e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.81, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.6538467}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3263663178842098e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.88, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.6738377}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3263663178842098e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.6938493}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3263663178842098e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.71387}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061312.7340555, "x": -88.23521887554999, "y": 40.09283877699143, "z": 202.96236688363427, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7108068162215617, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061312.733853}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3263663178842098e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.17, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.733853}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3263663178842098e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.17, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.7538717}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3263663178842098e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.7738645}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3263663178842098e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.18, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.7938316}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3263663178842098e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.18, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.8138695}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061312.833963, "x": -88.23522871197086, "y": 40.092837803050244, "z": 202.93370344224013, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.717393816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061312.8338597}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9139907366994787e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.24, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.8338597}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9139907366994787e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.24, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.8539414}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9139907366994787e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.43, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.873841}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9139907366994787e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.58, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.8938615}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9139907366994787e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.58, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.913832}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061312.9339504, "x": -88.23522871197086, "y": 40.092837803050244, "z": 202.93370344224013, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7517988162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061312.9338367}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9139907366994787e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.59, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.9338367}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9139907366994787e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.59, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.9538598}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9139907366994787e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.56, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.9738395}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9139907366994787e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.56, "gear": 0, "accelerator_pedal_position": 0.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": 1744061312.993837}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9139907366994787e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.69, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.013843}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061313.033959, "x": -88.23522871197086, "y": 40.092837803050244, "z": 202.93370344224013, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7715018162215617, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061313.0338593}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9139907366994787e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.78, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.0338593}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9139907366994787e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.78, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.053845}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9139907366994787e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.9, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.0738318}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9139907366994787e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.9, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.0938404}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9139907366994787e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.92, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.113855}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061313.1341562, "x": -88.23522871197086, "y": 40.092837803050244, "z": 202.93370344224013, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7974218162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061313.1338954}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9139907366994787e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.02, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.1338954}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9139907366994787e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.02, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.153868}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9139907366994787e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.09, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.1738694}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9139907366994787e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.09, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.1938596}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9139907366994787e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.22, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.2138746}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061313.2339814, "x": -88.23522871197086, "y": 40.092837803050244, "z": 202.93370344224013, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8268018162215616, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061313.2338405}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9139907366994787e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.28, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.2338405}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9139907366994787e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.28, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.2538486}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9139907366994787e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.29, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.2738714}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9139907366994787e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.29, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.2938492}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9139907366994787e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.37, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.3138506}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061313.3340316, "x": -88.23524504845084, "y": 40.09283612300876, "z": 202.92617007899165, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.843181816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061313.3338857}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9139907366994787e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.42, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.3338857}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9139907366994787e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.42, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.353888}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9139907366994787e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.58, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.373853}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.21905732308533e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.58, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.3938458}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.21905732308533e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.71, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.4138386}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061313.433941, "x": -88.23524504845084, "y": 40.09283612300876, "z": 202.92617007899165, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8783588162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061313.4338326}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.21905732308533e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.71, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.4338326}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.21905732308533e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.71, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.4538794}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.21905732308533e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.67, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.4738467}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.21905732308533e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.67, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.493832}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.21905732308533e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.83, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.5138335}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061313.5339448, "x": -88.23524504845084, "y": 40.09283612300876, "z": 202.92617007899165, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9100338162215618, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061313.533833}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.21905732308533e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.96, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.533833}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.21905732308533e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.96, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.5538876}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.21905732308533e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.02, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.573834}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.21905732308533e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.02, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.5938747}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.21905732308533e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.04, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.6138399}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061313.6339622, "x": -88.23524504845084, "y": 40.09283612300876, "z": 202.92617007899165, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9336138162215617, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061313.633836}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.21905732308533e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.14, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.633836}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.21905732308533e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.14, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.6538496}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.21905732308533e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.19, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.673834}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.21905732308533e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.19, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.693839}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.21905732308533e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.31, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.7138698}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061313.7339733, "x": -88.23524504845084, "y": 40.09283612300876, "z": 202.92617007899165, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9633138162215618, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061313.733839}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.21905732308533e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.36, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.733839}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.21905732308533e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.36, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.7538452}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.21905732308533e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.773831}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.21905732308533e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.7938576}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.21905732308533e-20, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.52, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.8138394}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061313.83398, "x": -88.23526783022868, "y": 40.092834050815235, "z": 202.882759016302, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9925668162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061313.8338382}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.419044375601044e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.57, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.8338382}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.419044375601044e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.57, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.853869}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.419044375601044e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.63, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.8738308}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.419044375601044e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.63, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.8938324}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.419044375601044e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.9138324}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061313.93402, "x": -88.23526783022868, "y": 40.092834050815235, "z": 202.882759016302, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.032942816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061313.9338942}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.419044375601044e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.85, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.9338942}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.419044375601044e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.85, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.9539347}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.419044375601044e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.89, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.9738653}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.419044375601044e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.89, "gear": 0, "accelerator_pedal_position": 0.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": 1744061313.9938648}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.419044375601044e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.0138903}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061314.033968, "x": -88.23526783022868, "y": 40.092834050815235, "z": 202.882759016302, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061314.0338397}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.419044375601044e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.0338397}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.419044375601044e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.0538545}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.419044375601044e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.0738328}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.419044375601044e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.0938425}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.419044375601044e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.1138341}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061314.133934, "x": -88.23526783022868, "y": 40.092834050815235, "z": 202.882759016302, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.090246816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061314.1338313}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.419044375601044e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.1338313}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.419044375601044e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.23, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.153879}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.419044375601044e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.1738315}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.419044375601044e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.1938565}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.419044375601044e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.2138317}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061314.233993, "x": -88.23526783022868, "y": 40.092834050815235, "z": 202.882759016302, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061314.2338822}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.419044375601044e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.2338822}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.419044375601044e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.253881}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.419044375601044e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.2738304}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.419044375601044e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.2938592}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.419044375601044e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.3138657}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061314.333963, "x": -88.23529702870269, "y": 40.09283155078289, "z": 202.8947158064588, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061314.3338292}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.419044375601044e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.3338292}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.419044375601044e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.3541894}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.419044375601044e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.3738356}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1825077970032125e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.393863}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1825077970032125e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.4138355}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061314.433989, "x": -88.23529702870269, "y": 40.09283155078289, "z": 202.8947158064588, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.168401816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061314.4338784}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1825077970032125e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.4338784}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1825077970032125e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.4539032}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1825077970032125e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.4738276}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1825077970032125e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.4939005}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1825077970032125e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.513863}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061314.5341718, "x": -88.23529702870269, "y": 40.09283155078289, "z": 202.8947158064588, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1966388162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061314.5338802}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1825077970032125e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.5338802}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1825077970032125e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.553834}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1825077970032125e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.573832}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1825077970032125e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.593841}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1825077970032125e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.6138568}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061314.633929, "x": -88.23529702870269, "y": 40.09283155078289, "z": 202.8947158064588, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.223742816221561, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061314.6338296}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1825077970032125e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.6338296}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1825077970032125e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.6538637}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1825077970032125e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.6738656}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1825077970032125e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.6940315}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1825077970032125e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.7138703}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061314.7339737, "x": -88.23529702870269, "y": 40.09283155078289, "z": 202.8947158064588, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.2531018162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061314.7338505}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1825077970032125e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.7338505}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1825077970032125e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.7539284}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1825077970032125e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.7738311}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1825077970032125e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.7938855}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.1825077970032125e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.8138592}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061314.8339727, "x": -88.2353312097024, "y": 40.09282783647862, "z": 202.8598850864553, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061314.833869}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0856320432237093e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.833869}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0856320432237093e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.8538709}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0856320432237093e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.8738637}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0856320432237093e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.8938854}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0856320432237093e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.913875}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061314.933955, "x": -88.2353312097024, "y": 40.09282783647862, "z": 202.8598850864553, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061314.9338617}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0856320432237093e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.9338617}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0856320432237093e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.9539628}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0856320432237093e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.54, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.9738326}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0856320432237093e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.54, "gear": 0, "accelerator_pedal_position": 0.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": 1744061314.993881}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0856320432237093e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.54, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.0138373}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061315.0339217, "x": -88.2353312097024, "y": 40.09282783647862, "z": 202.8598850864553, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3099338162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061315.0338256}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0856320432237093e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.54, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.0338256}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0856320432237093e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.54, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.0538998}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0856320432237093e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.073826}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0856320432237093e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.0938613}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0856320432237093e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.1138663}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061315.1339414, "x": -88.2353312097024, "y": 40.09282783647862, "z": 202.8598850864553, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.340958816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061315.133852}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0856320432237093e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.133852}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0856320432237093e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.1539993}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0856320432237093e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.1738324}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0856320432237093e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.1938303}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0856320432237093e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.213829}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061315.2340074, "x": -88.2353312097024, "y": 40.09282783647862, "z": 202.8598850864553, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061315.2338376}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0856320432237093e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.2338376}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0856320432237093e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.253869}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0856320432237093e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.2738526}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0856320432237093e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.2939}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0856320432237093e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.3138642}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061315.3339384, "x": -88.23536939016772, "y": 40.092823223121826, "z": 202.86263126369892, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.355758816221561, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061315.333847}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0856320432237093e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.333847}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0856320432237093e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.3538754}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0856320432237093e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.3738384}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.0999571842050575e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.3938448}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.0999571842050575e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.4138284}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061315.4339325, "x": -88.23536939016772, "y": 40.092823223121826, "z": 202.86263126369892, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.355758816221561, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061315.4338284}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.0999571842050575e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.4338284}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.0999571842050575e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.4538434}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.0999571842050575e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.4738283}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.0999571842050575e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.4938807}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.0999571842050575e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.5138247}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061315.5339298, "x": -88.23536939016772, "y": 40.092823223121826, "z": 202.86263126369892, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.355758816221561, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061315.5338285}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.0999571842050575e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.5338285}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.0999571842050575e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.55385}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.0999571842050575e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.573816}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.0999571842050575e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.5938253}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.0999571842050575e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.6138327}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061315.6339087, "x": -88.23536939016772, "y": 40.092823223121826, "z": 202.86263126369892, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.340958816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061315.633823}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.0999571842050575e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.633823}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.0999571842050575e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.653861}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.0999571842050575e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.673829}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.0999571842050575e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.6938322}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.0999571842050575e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.713824}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061315.7339215, "x": -88.23536939016772, "y": 40.092823223121826, "z": 202.86263126369892, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061315.7338266}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.0999571842050575e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.7338266}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.0999571842050575e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.7539132}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.0999571842050575e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.7738562}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.0999571842050575e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.7938645}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.0999571842050575e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.8138661}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061315.8339229, "x": -88.23540881607741, "y": 40.09281856259023, "z": 202.85548523374385, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.340958816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061315.8338237}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.146145158620413e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.8338237}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.146145158620413e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.8538465}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.146145158620413e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.8738258}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.146145158620413e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.8938384}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.146145158620413e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.54, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.9138591}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061315.9340773, "x": -88.23540881607741, "y": 40.09281856259023, "z": 202.85548523374385, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3099338162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061315.933865}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.146145158620413e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.54, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.933865}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.146145158620413e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.9538572}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.146145158620413e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.9738362}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.146145158620413e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.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": 1744061315.993829}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.146145158620413e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.0138376}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061316.0343316, "x": -88.23540881607741, "y": 40.09281856259023, "z": 202.85548523374385, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.237486816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061316.0338655}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.146145158620413e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.0338655}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.146145158620413e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.0539432}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.146145158620413e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.0738273}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.146145158620413e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.0938451}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.146145158620413e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.1138246}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061316.1340353, "x": -88.23540881607741, "y": 40.09281856259023, "z": 202.85548523374385, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.267117816221561, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061316.133837}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.146145158620413e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.133837}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.146145158620413e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.1538317}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.146145158620413e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.173827}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.146145158620413e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.1938329}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.146145158620413e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.213824}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061316.2339897, "x": -88.23540881607741, "y": 40.09281856259023, "z": 202.85548523374385, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.210126816221561, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061316.2338374}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.146145158620413e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.2338374}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.146145158620413e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.2538948}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.146145158620413e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.2738628}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.146145158620413e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.05, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.2938368}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.146145158620413e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.3138242}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061316.333981, "x": -88.23544582174374, "y": 40.09281426440087, "z": 202.8708827994479, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1966388162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061316.3338358}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.146145158620413e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.3338358}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.127197466936144e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.3538551}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.127197466936144e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.3738315}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.127197466936144e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.3938284}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.127197466936144e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.413828}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061316.434381, "x": -88.23544582174374, "y": 40.09281426440087, "z": 202.8708827994479, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.183278816221561, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061316.4338636}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.127197466936144e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.81, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.4338636}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.127197466936144e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.72, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.4538887}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.127197466936144e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.4738286}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.127197466936144e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.49383}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.127197466936144e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.5138264}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061316.5340319, "x": -88.23544582174374, "y": 40.09281426440087, "z": 202.8708827994479, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061316.5338514}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.127197466936144e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.5338514}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.127197466936144e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.553885}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.127197466936144e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.5738444}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.127197466936144e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.5938263}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.127197466936144e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.6138344}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061316.6339138, "x": -88.23544582174374, "y": 40.09281426440087, "z": 202.8708827994479, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.129521816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061316.6338253}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.127197466936144e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.48, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.6338253}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.127197466936144e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.6538758}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.127197466936144e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.6739254}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.127197466936144e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.6938267}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.127197466936144e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.7138271}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061316.7339187, "x": -88.23544582174374, "y": 40.09281426440087, "z": 202.8708827994479, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061316.7338254}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.127197466936144e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.7338254}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.127197466936144e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.7538767}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.127197466936144e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.773835}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.127197466936144e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.7938347}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.127197466936144e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.813837}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061316.8339286, "x": -88.23547818186321, "y": 40.09281031281714, "z": 202.8698825384063, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061316.8338277}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.127197466936144e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.8338277}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.127197466936144e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.853861}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.127197466936144e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.8738258}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.127197466936144e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.99, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.8938267}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.987391566856687e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.9138243}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061316.934497, "x": -88.23547818186321, "y": 40.09281031281714, "z": 202.8698825384063, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061316.9342241}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.987391566856687e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.9342241}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.987391566856687e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.9538517}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.987391566856687e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.9738395}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.987391566856687e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.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": 1744061316.9938352}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.987391566856687e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.013839}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061317.0342433, "x": -88.23547818186321, "y": 40.09281031281714, "z": 202.8698825384063, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.016893816221562, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061317.0339048}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.987391566856687e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.74, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.0339048}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.987391566856687e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.053853}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.987391566856687e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.073828}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.987391566856687e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.0938582}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.987391566856687e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.1138268}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061317.1341567, "x": -88.23547818186321, "y": 40.09281031281714, "z": 202.8698825384063, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9939818162215617, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061317.133847}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.987391566856687e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.58, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.133847}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.987391566856687e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.5, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.1538632}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.987391566856687e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.1738384}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.987391566856687e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.193856}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.987391566856687e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.2138283}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061317.2339144, "x": -88.23547818186321, "y": 40.09281031281714, "z": 202.8698825384063, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9592068162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061317.2338243}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.987391566856687e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.33, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.2338243}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.987391566856687e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.25, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.2539392}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.987391566856687e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.17, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.2738583}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.987391566856687e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.17, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.293829}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.987391566856687e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.17, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.3138568}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061317.3339765, "x": -88.23550560544973, "y": 40.092807018966674, "z": 202.87347137991523, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9376068162215616, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061317.3338368}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.987391566856687e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.17, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.3338368}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.987391566856687e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.17, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.353911}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.715715285050724e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.09, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.373848}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.715715285050724e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.09, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.393827}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.715715285050724e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.01, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.4138343}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061317.4339223, "x": -88.23550560544973, "y": 40.092807018966674, "z": 202.87347137991523, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9165188162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061317.4338284}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.715715285050724e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.01, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.4338284}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.715715285050724e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.86, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.4538858}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.715715285050724e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.9, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.4738293}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.715715285050724e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.9, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.4938326}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.715715285050724e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.86, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.5138688}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061317.5341468, "x": -88.23550560544973, "y": 40.092807018966674, "z": 202.87347137991523, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8972138162215613, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061317.5338647}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.715715285050724e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.86, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.5338647}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.715715285050724e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.79, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.5538976}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.715715285050724e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.71, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.5738363}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.715715285050724e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.71, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.5938573}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.715715285050724e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.67, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.6138604}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061317.6340208, "x": -88.23550560544973, "y": 40.092807018966674, "z": 202.87347137991523, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8734068162215616, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061317.63386}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.715715285050724e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.67, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.63386}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.715715285050724e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.62, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.6538985}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.715715285050724e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.58, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.673823}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.715715285050724e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.58, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.693869}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.715715285050724e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.48, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.7138534}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061317.7340317, "x": -88.23550560544973, "y": 40.092807018966674, "z": 202.87347137991523, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8503218162215616, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061317.733844}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.715715285050724e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.48, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.733844}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.715715285050724e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.46, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.7538354}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.715715285050724e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.4, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.7738466}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.715715285050724e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.4, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.7939508}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.715715285050724e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.32, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.8138611}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061317.834029, "x": -88.23552803627729, "y": 40.09280415114219, "z": 202.86490665455256, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8314418162215613, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061317.8338788}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.715715285050724e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.32, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.8338788}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.715715285050724e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.23, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.8538716}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.715715285050724e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.23, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.8738852}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.715715285050724e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.15, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.8938906}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.313499849900496e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.12, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.9138684}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061317.933983, "x": -88.23552803627729, "y": 40.09280415114219, "z": 202.86490665455256, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8085618162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061317.93387}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.313499849900496e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.12, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.93387}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.313499849900496e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.09, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.9538996}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.313499849900496e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.01, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.973838}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.313499849900496e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.01, "gear": 0, "accelerator_pedal_position": 0.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": 1744061317.9939816}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.313499849900496e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.97, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.0138793}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061318.0339756, "x": -88.23552803627729, "y": 40.09280415114219, "z": 202.86490665455256, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7919268162215616, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061318.033861}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.313499849900496e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.97, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.033861}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.313499849900496e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.9, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.0538583}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.313499849900496e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.83, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.0738566}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.313499849900496e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.83, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.0938668}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.313499849900496e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.83, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.1138372}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061318.1340396, "x": -88.23552803627729, "y": 40.09280415114219, "z": 202.86490665455256, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7768068162215616, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061318.1339164}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.313499849900496e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.83, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.1339164}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.313499849900496e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.74, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.1539197}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.313499849900496e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.74, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.1738482}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.313499849900496e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.67, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.1938314}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.313499849900496e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.63, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.2138247}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061318.233959, "x": -88.23552803627729, "y": 40.09280415114219, "z": 202.86490665455256, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7558868162215617, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061318.233832}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.313499849900496e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.63, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.233832}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.313499849900496e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.62, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.2538414}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.313499849900496e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.62, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.2738225}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.313499849900496e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.53, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.2938585}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.313499849900496e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.5, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.3138227}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061318.3340175, "x": -88.2355457570608, "y": 40.09280208651131, "z": 202.88061805282058, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7427178162215617, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061318.333844}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.313499849900496e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.5, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.333844}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.783368332736647e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.42, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.353915}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.783368332736647e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.42, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.3738642}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.783368332736647e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.34, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.3938243}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.783368332736647e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.33, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.413876}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061318.434235, "x": -88.2355457570608, "y": 40.09280208651131, "z": 202.88061805282058, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7260068162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061318.4338734}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.783368332736647e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.33, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.4338734}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.783368332736647e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.31, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.453917}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.783368332736647e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.31, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.4739206}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.783368332736647e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.22, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.4938633}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.783368332736647e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.17, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.513832}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061318.534285, "x": -88.2355457570608, "y": 40.09280208651131, "z": 202.88061805282058, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7108068162215617, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061318.5338342}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.783368332736647e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.17, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.5338342}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.783368332736647e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.06, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.553837}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.783368332736647e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.06, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.5738513}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.783368332736647e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.03, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.5938632}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.783368332736647e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.99, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.6138685}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061318.633954, "x": -88.2355457570608, "y": 40.09280208651131, "z": 202.88061805282058, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6943188162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061318.6338549}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.783368332736647e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.99, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.6338549}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.783368332736647e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.94, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.653875}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.783368332736647e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.94, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.6738796}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.783368332736647e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.87, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.6938741}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.783368332736647e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.85, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.713821}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061318.7340403, "x": -88.2355457570608, "y": 40.09280208651131, "z": 202.88061805282058, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6819428162215617, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061318.7338414}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.783368332736647e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.85, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.7338414}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.783368332736647e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.77, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.753825}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.783368332736647e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.77, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.7738204}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.783368332736647e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.71, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.7938259}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.783368332736647e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.69, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.8138704}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061318.8341396, "x": -88.2355585714798, "y": 40.09280057558135, "z": 202.89998007649822, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6682788162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061318.833891}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.783368332736647e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.69, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.833891}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.783368332736647e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.62, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.853874}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.783368332736647e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.62, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.8738487}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.783368332736647e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.55, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.8938525}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.783368332736647e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.51, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.9138873}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061318.9339151, "x": -88.2355585714798, "y": 40.09280057558135, "z": 202.89998007649822, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6535188162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061318.933824}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.123359337872287e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.51, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.933824}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.123359337872287e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.47, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.9539232}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.123359337872287e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.47, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.9739254}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.123359337872287e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.39, "gear": 0, "accelerator_pedal_position": 0.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": 1744061318.9938612}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.123359337872287e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.35, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.0138588}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061319.033951, "x": -88.2355585714798, "y": 40.09280057558135, "z": 202.89998007649822, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6409428162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061319.0338538}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.123359337872287e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.35, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.0338538}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.123359337872287e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.0538864}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.123359337872287e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.0738583}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.123359337872287e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.23, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.0938601}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.123359337872287e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.19, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.1138625}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061319.1339393, "x": -88.2355585714798, "y": 40.09280057558135, "z": 202.89998007649822, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6288788162215617, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061319.1338453}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.123359337872287e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.19, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.1338453}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.123359337872287e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.16, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.1538866}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.123359337872287e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.16, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.1738563}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.123359337872287e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.11, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.193857}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.123359337872287e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.04, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.2138543}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061319.2340305, "x": -88.2355585714798, "y": 40.09280057558135, "z": 202.89998007649822, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6180338162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061319.233862}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.123359337872287e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.04, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.233862}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.123359337872287e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.99, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.2538922}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.123359337872287e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.99, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.2738278}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.123359337872287e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.96, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.2938654}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.123359337872287e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.3138857}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061319.3339522, "x": -88.23556643792554, "y": 40.09279964260947, "z": 202.87876259429902, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6083178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061319.33383}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.123359337872287e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.33383}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.332133759821368e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.89, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.3538318}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.332133759821368e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.89, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.3738925}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.332133759821368e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.82, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.3938754}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.332133759821368e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.74, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.4138527}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061319.4339507, "x": -88.23556643792554, "y": 40.09279964260947, "z": 202.87876259429902, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5976938162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061319.4338505}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.332133759821368e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.74, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.4338505}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.332133759821368e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.72, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.4538422}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.332133759821368e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.72, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.473862}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.332133759821368e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.67, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.4938626}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.332133759821368e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.63, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.5138783}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061319.5342786, "x": -88.23556643792554, "y": 40.09279964260947, "z": 202.87876259429902, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5906868162215617, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061319.5339103}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.332133759821368e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.63, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.5339103}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.332133759821368e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.5538604}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.332133759821368e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.5738528}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.332133759821368e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.54, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.5938249}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.332133759821368e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.49, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.6138575}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061319.6339467, "x": -88.23556643792554, "y": 40.09279964260947, "z": 202.87876259429902, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5821188162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061319.633857}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.332133759821368e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.49, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.633857}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.332133759821368e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.47, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.6538696}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.332133759821368e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.47, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.6738307}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.332133759821368e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.43, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.6938694}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.332133759821368e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.39, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.7138584}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061319.733939, "x": -88.23556643792554, "y": 40.09279964260947, "z": 202.87876259429902, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5762388162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061319.7338533}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.332133759821368e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.39, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.7338533}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.332133759821368e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.37, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.7538676}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.332133759821368e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.37, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.7738216}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.332133759821368e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.31, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.7938423}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.332133759821368e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.26, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.8138258}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061319.8339036, "x": -88.23557009844247, "y": 40.09279935567334, "z": 202.8884884351005, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5688938162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061319.8338203}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.332133759821368e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.26, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.8338203}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.332133759821368e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.24, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.8538756}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.332133759821368e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.24, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.8738427}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.332133759821368e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.21, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.8938525}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.427533209878214e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.17, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.913853}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061319.9339142, "x": -88.23557009844247, "y": 40.09279935567334, "z": 202.8884884351005, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5640068162215615, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061319.9338222}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.427533209878214e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.17, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.9338222}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.427533209878214e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.15, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.9538836}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.427533209878214e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.15, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.9738271}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.427533209878214e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.09, "gear": 0, "accelerator_pedal_position": 0.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": 1744061319.9938242}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.427533209878214e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.07, "gear": 0, "accelerator_pedal_position": 0.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": 1744061320.0138297}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061320.034063, "x": -88.23557009844247, "y": 40.09279935567334, "z": 202.8884884351005, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5587668162215618, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061320.0338557}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.427533209878214e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.07, "gear": 0, "accelerator_pedal_position": 0.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": 1744061320.0338557}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.427533209878214e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.04, "gear": 0, "accelerator_pedal_position": 0.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": 1744061320.053853}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.427533209878214e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.04, "gear": 0, "accelerator_pedal_position": 0.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": 1744061320.0738223}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.427533209878214e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.03, "gear": 0, "accelerator_pedal_position": 0.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": 1744061320.0938485}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.427533209878214e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.02, "gear": 0, "accelerator_pedal_position": 0.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": 1744061320.113853}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061320.1339025, "x": -88.23557009844247, "y": 40.09279935567334, "z": 202.8884884351005, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5562218162215617, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061320.1338198}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.427533209878214e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.02, "gear": 0, "accelerator_pedal_position": 0.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": 1744061320.1338198}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.427533209878214e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01, "gear": 0, "accelerator_pedal_position": 0.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": 1744061320.1538334}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.427533209878214e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01, "gear": 0, "accelerator_pedal_position": 0.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": 1744061320.1738203}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.427533209878214e-19, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01, "gear": 0, "accelerator_pedal_position": 0.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": 1744061320.19385}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.427533209878214e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.2138216}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061320.2339215, "x": -88.23557009844247, "y": 40.09279935567334, "z": 202.8884884351005, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061320.2338223}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.427533209878214e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.2338223}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.427533209878214e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.2538865}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.427533209878214e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.2738247}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.427533209878214e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.293825}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.427533209878214e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.313828}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061320.3341184, "x": -88.23557050013044, "y": 40.09279931610668, "z": 202.8835785022218, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061320.3339095}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.438096389014912e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.3339095}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.438096389014912e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.353824}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.438096389014912e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.373822}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.438096389014912e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.3938503}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.438096389014912e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.4138196}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061320.4339159, "x": -88.23557050013044, "y": 40.09279931610668, "z": 202.8835785022218, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061320.433821}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.438096389014912e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.433821}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.438096389014912e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.4540722}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.438096389014912e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.4738214}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.438096389014912e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.4938989}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.438096389014912e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.5138636}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061320.533911, "x": -88.23557050013044, "y": 40.09279931610668, "z": 202.8835785022218, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061320.533822}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.438096389014912e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.533822}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.438096389014912e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.5538275}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.438096389014912e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.5738232}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.438096389014912e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.5938234}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.438096389014912e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.6138217}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061320.6339145, "x": -88.23557050013044, "y": 40.09279931610668, "z": 202.8835785022218, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061320.6338227}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.438096389014912e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.6338227}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.438096389014912e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.6538522}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.438096389014912e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.6738257}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.438096389014912e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.693824}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.438096389014912e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.7138443}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061320.7339106, "x": -88.23557050013044, "y": 40.09279931610668, "z": 202.8835785022218, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061320.7338262}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.438096389014912e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.7338262}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.438096389014912e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.7538443}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.438096389014912e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.7738516}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.438096389014912e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.7938302}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.438096389014912e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.813856}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061320.8341863, "x": -88.23557012375828, "y": 40.0927999908247, "z": 202.89403647309567, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061320.8339775}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.438096389014912e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.8339775}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.438096389014912e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.8538296}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.438096389014912e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.8738234}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.420609246831919e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.8939433}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.420609246831919e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.9138887}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061320.933972, "x": -88.23557012375828, "y": 40.0927999908247, "z": 202.89403647309567, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061320.9338496}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.420609246831919e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.9338496}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.420609246831919e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.9538944}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.420609246831919e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.9738224}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.420609246831919e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061320.9938784}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.420609246831919e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061321.0138495}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061321.0339913, "x": -88.23557012375828, "y": 40.0927999908247, "z": 202.89403647309567, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061321.033869}
+{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.8, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.420609246831919e-19, "steering_wheel_speed": 4.0, "left_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": 0, "accelerator_pedal_position": 0.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": 1744061321.033869}
diff --git a/testing/racing_logs/launch_control_2/meta.yaml b/testing/racing_logs/launch_control_2/meta.yaml
new file mode 100644
index 000000000..4c05a311f
--- /dev/null
+++ b/testing/racing_logs/launch_control_2/meta.yaml
@@ -0,0 +1,19 @@
+events:
+- description: Ctrl+C pressed, switching to recovery mode
+ time: 1744061321.035963
+ vehicle_time: 1744061321.033869
+- description: Mission execution ended
+ time: 1744061321.042774
+ vehicle_time: 1744061321.033869
+exit_reason: normal exit
+git_branch: racing
+git_commit_id: 2e36aeb7a55246289008a8f0a7de7f84bdbec5e6
+pipelines:
+- name: drive
+ time: 1744061305.7325842
+ vehicle_time: 1744061305.6323853
+- name: recovery
+ time: 1744061321.0373304
+ vehicle_time: 1744061321.033869
+start_time: 1744061305.618194
+start_time_human_readable: '2025-04-07 16:28:25'
diff --git a/testing/racing_logs/launch_control_2/settings.yaml b/testing/racing_logs/launch_control_2/settings.yaml
new file mode 100644
index 000000000..b5981eb6c
--- /dev/null
+++ b/testing/racing_logs/launch_control_2/settings.yaml
@@ -0,0 +1,327 @@
+control:
+ longitudinal_control:
+ pid_d: 0.0
+ pid_i: 0.03
+ pid_p: 0.8
+ pure_pursuit:
+ crosstrack_gain: 0.3
+ desired_speed: trajectory
+ launch_control: 0
+ lookahead: 2.0
+ lookahead_scale: 2.0
+ recovery:
+ brake_amount: 0.5
+ brake_speed: 2.0
+model_predictive_controller:
+ dt: 0.1
+ lookahead: 20
+planning:
+ longitudinal_plan:
+ acceleration: 0.5
+ deceleration: 2.0
+ desired_speed: 1.0
+ max_deceleration: 6.0
+ min_deceleration: 0.5
+ mode: real
+ planner: dt
+ yield_deceleration: 0.5
+ yielder: expert
+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:
+ - all
+ 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:
+ perception_normalization: StandardPerceptionNormalizer
+ state_estimation: GNSSStateEstimator
+ 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: hardware
+ 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: gem_hardware.GEMHardwareInterface
+simulator:
+ dt: 0.01
+ gnss_emulator:
+ dt: 0.05
+ real_time_multiplier: 1.0
+vehicle:
+ calibration:
+ calibration_date: '2025-02-25'
+ front_camera:
+ center_position:
+ - 1.75864913
+ - 0.01238124
+ - 1.54408419
+ reference: rear_axle_center
+ rotation:
+ - - 0.00349517
+ - -0.03239524
+ - 0.99946903
+ - - -0.99996547
+ - 0.00742285
+ - 0.0037375
+ - - -0.00753999
+ - -0.99944757
+ - -0.03236817
+ gnss_location:
+ - 1.1
+ - 0
+ - 1.62
+ gnss_yaw: 0.0
+ rear_axle_height: 0.2794
+ reference: rear_axle_center
+ top_lidar:
+ position:
+ - 1.1
+ - 0.03773044170906172
+ - 1.9525244316515322
+ reference: rear_axle_center
+ rotation:
+ - - 0.99941328
+ - 0.02547416
+ - 0.02289458
+ - - -0.02530855
+ - 0.99965159
+ - -0.00749488
+ - - -0.02307753
+ - 0.00691106
+ - 0.99970979
+ control_defaults:
+ accelerator_pedal_speed: 3.0
+ brake_pedal_speed: 3.0
+ steering_wheel_speed: 4.0
+ dynamics:
+ acceleration_deadband: 0.1
+ acceleration_model: hang_v1
+ accelerator_active_range:
+ - 0.2
+ - 1.0
+ aerodynamic_drag_coefficient: 0.01
+ brake_active_range:
+ - 0.5
+ - 1
+ gravity: 9.81
+ internal_dry_deceleration: 0.2
+ internal_viscous_deceleration: 0.05
+ lateral_friction: 1.0
+ longitudinal_friction: 1.0
+ mass: 700.0
+ max_accelerator_acceleration:
+ - 0.0
+ - 5.0
+ max_accelerator_acceleration_reverse: 2.5
+ max_accelerator_power:
+ - 0.0
+ - 5000.0
+ max_accelerator_power_reverse: 5000.0
+ max_brake_deceleration: 8.0
+ pedal_mapping_function: linear
+ velocity_scaling_factor: 0.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/gem/racing2/src/GEMstack/GEMstack/knowledge/vehicle/model/gem_e4.urdf
+ wheel_radius: 0.33
+ wheelbase: 2.56
+ width: 1.7
+ limits:
+ max_acceleration: 3.0
+ max_accelerator_pedal: 1.0
+ max_brake_pedal: 1.0
+ max_deceleration: 5.0
+ max_reverse_speed: 2.5
+ max_speed: 10.0
+ max_steering_rate: 4.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/testing/racing_logs/manual_launch_control/behavior.json b/testing/racing_logs/manual_launch_control/behavior.json
new file mode 100644
index 000000000..6cb74754d
--- /dev/null
+++ b/testing/racing_logs/manual_launch_control/behavior.json
@@ -0,0 +1,236 @@
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061246.5640283, "x": -88.23532023028547, "y": 40.09283096141204, "z": 203.13815846077335, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.092, "front_wheel_angle": -0.004230132597423936, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061246.563198}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061246.563198}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061246.6644619, "x": -88.23532023028547, "y": 40.09283096141204, "z": 203.13815846077335, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.092, "front_wheel_angle": -0.004230132597423936, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061246.6643636}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061246.6643636}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061246.764595, "x": -88.23532023028547, "y": 40.09283096141204, "z": 203.13815846077335, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.092, "front_wheel_angle": -0.004230132597423936, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061246.7645025}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061246.7645025}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061246.8645875, "x": -88.23532012154463, "y": 40.092830788224, "z": 203.11291854827812, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.092, "front_wheel_angle": -0.004230132597423936, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061246.8644783}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061246.8644783}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061246.9646652, "x": -88.23532012154463, "y": 40.092830788224, "z": 203.11291854827812, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.092, "front_wheel_angle": -0.004230132597423936, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061246.9645302}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061246.9645302}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061247.0645692, "x": -88.23532012154463, "y": 40.092830788224, "z": 203.11291854827812, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.092, "front_wheel_angle": -0.004230132597423936, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061247.0644763}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061247.0644763}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061247.1645687, "x": -88.23532012154463, "y": 40.092830788224, "z": 203.11291854827812, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.092, "front_wheel_angle": -0.004230132597423936, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061247.164474}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061247.164474}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061247.2646086, "x": -88.23532012154463, "y": 40.092830788224, "z": 203.11291854827812, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.092, "front_wheel_angle": -0.004230132597423936, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061247.2645001}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061247.2645001}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061247.3646164, "x": -88.23531990353848, "y": 40.0928306283866, "z": 203.11038322927516, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.092, "front_wheel_angle": -0.004230132597423936, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061247.3645086}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061247.3645086}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061247.4645798, "x": -88.23531990353848, "y": 40.0928306283866, "z": 203.11038322927516, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.092, "front_wheel_angle": -0.004230132597423936, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061247.464475}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061247.464475}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061247.564584, "x": -88.23531990353848, "y": 40.0928306283866, "z": 203.11038322927516, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.092, "front_wheel_angle": -0.004230132597423936, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061247.5644765}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061247.5644765}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061247.6645858, "x": -88.23531990353848, "y": 40.0928306283866, "z": 203.11038322927516, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.092, "front_wheel_angle": -0.004230132597423936, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061247.6644788}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061247.6644788}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061247.7646985, "x": -88.23531990353848, "y": 40.0928306283866, "z": 203.11038322927516, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.092, "front_wheel_angle": -0.004230132597423936, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061247.7645018}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061247.7645018}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061247.8645644, "x": -88.2353199872983, "y": 40.09283043239774, "z": 203.0656400813499, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.092, "front_wheel_angle": -0.004230132597423936, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061247.8644714}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061247.8644714}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061247.964596, "x": -88.2353199872983, "y": 40.09283043239774, "z": 203.0656400813499, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.092, "front_wheel_angle": -0.004230132597423936, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061247.9645033}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061247.9645033}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061248.0646052, "x": -88.2353199872983, "y": 40.09283043239774, "z": 203.0656400813499, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.092, "front_wheel_angle": -0.004230132597423936, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061248.0644805}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061248.0644805}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061248.1646364, "x": -88.2353199872983, "y": 40.09283043239774, "z": 203.0656400813499, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.092, "front_wheel_angle": -0.004230132597423936, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061248.164504}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061248.164504}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061248.264625, "x": -88.2353199872983, "y": 40.09283043239774, "z": 203.0656400813499, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.092, "front_wheel_angle": -0.004230132597423936, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061248.2644913}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061248.2644913}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061248.3645926, "x": -88.23531985385672, "y": 40.092830133214456, "z": 203.06647230289838, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5582538162215616, "steering_wheel_angle": -0.092, "front_wheel_angle": -0.004230132597423936, "heading_rate": -9.914432411639438e-05, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061248.3644996}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061248.3644996}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061248.464628, "x": -88.23531985385672, "y": 40.092830133214456, "z": 203.06647230289838, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.571678816221562, "steering_wheel_angle": -0.092, "front_wheel_angle": -0.004230132597423936, "heading_rate": -0.000512245674601371, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061248.4645195}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061248.4645195}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061248.5646064, "x": -88.23531985385672, "y": 40.092830133214456, "z": 203.06647230289838, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5587668162215618, "steering_wheel_angle": -0.092, "front_wheel_angle": -0.004230132597423936, "heading_rate": -0.00011566837813579345, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061248.5645041}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061248.5645041}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061248.6648078, "x": -88.23531985385672, "y": 40.092830133214456, "z": 203.06647230289838, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5750868162215617, "steering_wheel_angle": -0.092, "front_wheel_angle": -0.004230132597423936, "heading_rate": -0.0006113899987177653, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061248.6645076}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.37, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061248.6645076}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061248.7646008, "x": -88.23531985385672, "y": 40.092830133214456, "z": 203.06647230289838, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5656178162215615, "steering_wheel_angle": -0.092, "front_wheel_angle": -0.004230132597423936, "heading_rate": -0.0003304810803879813, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061248.764505}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061248.764505}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061248.8646226, "x": -88.23531990481513, "y": 40.0928297911967, "z": 203.06578805580088, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5925738162215617, "steering_wheel_angle": -0.092, "front_wheel_angle": -0.004230132597423936, "heading_rate": -0.0010905875652803382, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061248.8645225}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061248.8645225}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061248.9646118, "x": -88.23531990481513, "y": 40.0928297911967, "z": 203.06578805580088, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5797428162215614, "steering_wheel_angle": -0.092, "front_wheel_angle": -0.004230132597423936, "heading_rate": -0.0007435824308729579, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061248.964475}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.45, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061248.964475}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061249.0645924, "x": -88.23531990481513, "y": 40.0928297911967, "z": 203.06578805580088, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6062868162215613, "steering_wheel_angle": -0.092, "front_wheel_angle": -0.004230132597423936, "heading_rate": -0.0014375926996877185, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061249.0644774}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061249.0644774}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061249.164611, "x": -88.23531990481513, "y": 40.0928297911967, "z": 203.06578805580088, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6124338162215617, "steering_wheel_angle": -0.092, "front_wheel_angle": -0.004230132597423936, "heading_rate": -0.00158630918586231, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061249.1645033}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.96, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061249.1645033}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061249.2646039, "x": -88.23531990481513, "y": 40.0928297911967, "z": 203.06578805580088, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6252138162215615, "steering_wheel_angle": -0.092, "front_wheel_angle": -0.004230132597423936, "heading_rate": -0.001883742158211493, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061249.2644928}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.14, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061249.2644928}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061249.3646386, "x": -88.2353235547257, "y": 40.09282931721956, "z": 203.0609485537916, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6583668162215615, "steering_wheel_angle": -0.091, "front_wheel_angle": -0.004184097889882324, "heading_rate": -0.0025660437583450387, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061249.364502}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.091, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061249.364502}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061249.4645624, "x": -88.2353235547257, "y": 40.09282931721956, "z": 203.0609485537916, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6559338162215615, "steering_wheel_angle": -0.091, "front_wheel_angle": -0.004184097889882324, "heading_rate": -0.0025170110750645605, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061249.4644704}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.54, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.091, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061249.4644704}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061249.5646038, "x": -88.2353235547257, "y": 40.09282931721956, "z": 203.0609485537916, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.691633816221562, "steering_wheel_angle": -0.091, "front_wheel_angle": -0.004184097889882324, "heading_rate": -0.0032034686409912584, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061249.5645103}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.96, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.091, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061249.5645103}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061249.6646059, "x": -88.2353235547257, "y": 40.09282931721956, "z": 203.0609485537916, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7098738162215614, "steering_wheel_angle": -0.091, "front_wheel_angle": -0.004184097889882324, "heading_rate": -0.0035303531961944482, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061249.6644807}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.16, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.091, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061249.6644807}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061249.7645833, "x": -88.2353235547257, "y": 40.09282931721956, "z": 203.0609485537916, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7250418162215615, "steering_wheel_angle": -0.091, "front_wheel_angle": -0.004184097889882324, "heading_rate": -0.0037918608403569995, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061249.7644742}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.32, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.091, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061249.7644742}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061249.864642, "x": -88.23533398097787, "y": 40.09282847306483, "z": 203.0304610226729, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7600068162215616, "steering_wheel_angle": -0.091, "front_wheel_angle": -0.004184097889882324, "heading_rate": -0.004363908811962581, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061249.8644946}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.091, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061249.8644946}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061249.964626, "x": -88.23533398097787, "y": 40.09282847306483, "z": 203.0304610226729, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7757418162215615, "steering_wheel_angle": -0.091, "front_wheel_angle": -0.004184097889882324, "heading_rate": -0.004609072228364973, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061249.9645073}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.091, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061249.9645073}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061250.0646138, "x": -88.23533398097787, "y": 40.09282847306483, "z": 203.0304610226729, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.801853816221562, "steering_wheel_angle": -0.091, "front_wheel_angle": -0.004184097889882324, "heading_rate": -0.005001333694608802, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061250.0645118}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.091, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061250.0645118}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061250.164643, "x": -88.23533398097787, "y": 40.09282847306483, "z": 203.0304610226729, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8314418162215613, "steering_wheel_angle": -0.09, "front_wheel_angle": -0.0041380643941128885, "heading_rate": -0.005366582892848458, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061250.1644924}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.32, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.09, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061250.1644924}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061250.2645845, "x": -88.23533398097787, "y": 40.09282847306483, "z": 203.0304610226729, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8563268162215616, "steering_wheel_angle": -0.088, "front_wheel_angle": -0.004046001037507012, "heading_rate": -0.005579086561605136, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061250.264476}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.53, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.088, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061250.264476}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061250.364617, "x": -88.23535132775933, "y": 40.092826799837134, "z": 203.00436488880734, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8858468162215614, "steering_wheel_angle": -0.088, "front_wheel_angle": -0.004046001037507012, "heading_rate": -0.005958401228683106, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061250.3644996}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.77, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.088, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061250.3644996}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061250.4646168, "x": -88.23535132775933, "y": 40.092826799837134, "z": 203.00436488880734, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9243668162215615, "steering_wheel_angle": -0.087, "front_wheel_angle": -0.0039999711764795165, "heading_rate": -0.00635936309125664, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061250.4644785}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.087, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061250.4644785}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061250.5646243, "x": -88.23535132775933, "y": 40.092826799837134, "z": 203.00436488880734, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9429588162215614, "steering_wheel_angle": -0.086, "front_wheel_angle": -0.003953942526841233, "heading_rate": -0.006502415931652903, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061250.5645044}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.21, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.086, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061250.5645044}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061250.6646557, "x": -88.23535132775933, "y": 40.092826799837134, "z": 203.00436488880734, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.986926816221562, "steering_wheel_angle": -0.085, "front_wheel_angle": -0.00390791508849692, "heading_rate": -0.006915213074062112, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061250.6645045}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.53, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.085, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061250.6645045}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061250.764673, "x": -88.23535132775933, "y": 40.092826799837134, "z": 203.00436488880734, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.028541816221562, "steering_wheel_angle": -0.08, "front_wheel_angle": -0.003677796062834341, "heading_rate": -0.006924631620863638, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061250.76451}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.08, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061250.76451}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061250.8649461, "x": -88.23537518727704, "y": 40.092824807905416, "z": 203.01752346254855, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.047742816221562, "steering_wheel_angle": -0.077, "front_wheel_angle": -0.0035397391768435885, "heading_rate": -0.00684444613540629, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061250.8645647}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.077, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061250.8645647}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061250.964609, "x": -88.23537518727704, "y": 40.092824807905416, "z": 203.01752346254855, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.065766816221561, "steering_wheel_angle": -0.069, "front_wheel_angle": -0.0031716407329421357, "heading_rate": -0.006281356419859673, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061250.964482}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.069, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061250.964482}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061251.0646467, "x": -88.23537518727704, "y": 40.092824807905416, "z": 203.01752346254855, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.116817816221562, "steering_wheel_angle": -0.056, "front_wheel_angle": -0.0025736458598437915, "heading_rate": -0.005428796221767439, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061251.0645118}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.4, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.056, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061251.0645118}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061251.164594, "x": -88.23537518727704, "y": 40.092824807905416, "z": 203.01752346254855, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.142353816221561, "steering_wheel_angle": -0.05, "front_wheel_angle": -0.002297717119318425, "heading_rate": -0.0049903631507368, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061251.1645012}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.56, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.05, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061251.1645012}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061251.264646, "x": -88.23537518727704, "y": 40.092824807905416, "z": 203.01752346254855, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": -0.05, "front_wheel_angle": -0.002297717119318425, "heading_rate": -0.0050621669370783376, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061251.26451}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.05, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061251.26451}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061251.3645763, "x": -88.2354050078106, "y": 40.092821837673675, "z": 202.97555760049337, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1966388162215615, "steering_wheel_angle": -0.05, "front_wheel_angle": -0.002297717119318425, "heading_rate": -0.0052865537693956395, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061251.3644745}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.05, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061251.3644745}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061251.4645865, "x": -88.2354050078106, "y": 40.092821837673675, "z": 202.97555760049337, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.210126816221561, "steering_wheel_angle": -0.045, "front_wheel_angle": -0.002067809719214362, "heading_rate": -0.004822203757249382, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061251.4644744}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.97, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.045, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061251.4644744}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061251.5646257, "x": -88.2354050078106, "y": 40.092821837673675, "z": 202.97555760049337, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.2531018162215615, "steering_wheel_angle": -0.043, "front_wheel_angle": -0.0019758552115223572, "heading_rate": -0.00480071695658646, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061251.5645041}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.22, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.043, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061251.5645041}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061251.664624, "x": -88.2354050078106, "y": 40.092821837673675, "z": 202.97555760049337, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": -0.043, "front_wheel_angle": -0.0019758552115223572, "heading_rate": -0.004924208068009906, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061251.6645124}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.043, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061251.6645124}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061251.764601, "x": -88.2354050078106, "y": 40.092821837673675, "z": 202.97555760049337, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.281261816221562, "steering_wheel_angle": -0.043, "front_wheel_angle": -0.0019758552115223572, "heading_rate": -0.004924208068009906, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061251.764503}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.38, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.043, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061251.764503}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061251.8646033, "x": -88.23544033238866, "y": 40.092817895132875, "z": 202.990058690328, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.324461816221562, "steering_wheel_angle": -0.043, "front_wheel_angle": -0.0019758552115223572, "heading_rate": -0.005109444735145075, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061251.8645055}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.62, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.043, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061251.8645055}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061251.9646018, "x": -88.23544033238866, "y": 40.092817895132875, "z": 202.990058690328, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.340958816221562, "steering_wheel_angle": -0.043, "front_wheel_angle": -0.0019758552115223572, "heading_rate": -0.005178908485320763, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061251.9645088}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.043, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061251.9645088}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061252.0645652, "x": -88.23544033238866, "y": 40.092817895132875, "z": 202.990058690328, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.355758816221561, "steering_wheel_angle": -0.042, "front_wheel_angle": -0.0019298797685140421, "heading_rate": -0.005118710897041489, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061252.064469}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.79, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.042, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061252.064469}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061252.164576, "x": -88.23544033238866, "y": 40.092817895132875, "z": 202.990058690328, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.385742816221562, "steering_wheel_angle": -0.042, "front_wheel_angle": -0.0019298797685140421, "heading_rate": -0.005239328532317872, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061252.1644695}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.95, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.042, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061252.1644695}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061252.2645907, "x": -88.23544033238866, "y": 40.092817895132875, "z": 202.990058690328, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.400926816221562, "steering_wheel_angle": -0.042, "front_wheel_angle": -0.0019298797685140421, "heading_rate": -0.005299637349956063, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061252.264472}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.03, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.042, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061252.264472}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061252.3646367, "x": -88.23544033238866, "y": 40.092817895132875, "z": 202.990058690328, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": -0.042, "front_wheel_angle": -0.0019298797685140421, "heading_rate": -0.00542779358743722, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061252.3644917}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.042, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061252.3644917}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061252.4647415, "x": -88.2354793391444, "y": 40.092814561736816, "z": 202.98095840804882, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": -0.042, "front_wheel_angle": -0.0019298797685140421, "heading_rate": -0.00542779358743722, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061252.4645274}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.042, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061252.4645274}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061252.5645976, "x": -88.2354793391444, "y": 40.092814561736816, "z": 202.98095840804882, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.464913816221562, "steering_wheel_angle": -0.042, "front_wheel_angle": -0.0019298797685140421, "heading_rate": -0.005548411222713602, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061252.5644763}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.042, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061252.5644763}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061252.6647189, "x": -88.2354793391444, "y": 40.092814561736816, "z": 202.98095840804882, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": -0.042, "front_wheel_angle": -0.0019298797685140421, "heading_rate": -0.005367484769799028, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061252.6645463}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.042, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061252.6645463}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061252.764567, "x": -88.2354793391444, "y": 40.092814561736816, "z": 202.98095840804882, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.464913816221562, "steering_wheel_angle": -0.042, "front_wheel_angle": -0.0019298797685140421, "heading_rate": -0.005548411222713602, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061252.764469}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.36, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.042, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061252.764469}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061252.8645973, "x": -88.23552153641958, "y": 40.09280998252958, "z": 202.97562238402358, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": -0.044, "front_wheel_angle": -0.002021831861724432, "heading_rate": -0.005686409859411878, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061252.8644953}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.044, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061252.8644953}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061252.9646187, "x": -88.23552153641958, "y": 40.09280998252958, "z": 202.97562238402358, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.433617816221561, "steering_wheel_angle": -0.043, "front_wheel_angle": -0.0019758552115223572, "heading_rate": -0.005557100014055067, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061252.9645}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.043, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061252.9645}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061253.0645995, "x": -88.23552153641958, "y": 40.09280998252958, "z": 202.97562238402358, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": -0.044, "front_wheel_angle": -0.002021831861724432, "heading_rate": -0.005623227527640635, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061253.064495}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.044, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061253.064495}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061253.1646163, "x": -88.23552153641958, "y": 40.09280998252958, "z": 202.97562238402358, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.418161816221562, "steering_wheel_angle": -0.044, "front_wheel_angle": -0.002021831861724432, "heading_rate": -0.005623227527640635, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061253.164506}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.12, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.044, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061253.164506}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061253.2647357, "x": -88.23552153641958, "y": 40.09280998252958, "z": 202.97562238402358, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.449201816221562, "steering_wheel_angle": -0.044, "front_wheel_angle": -0.002021831861724432, "heading_rate": -0.005749592191183122, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061253.264522}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 7.28, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.044, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061253.264522}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061253.3645904, "x": -88.23556436895211, "y": 40.092805752936044, "z": 202.95895964487252, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": -0.044, "front_wheel_angle": -0.002021831861724432, "heading_rate": -0.005425782740855501, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061253.364499}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.044, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061253.364499}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061253.4646327, "x": -88.23556436895211, "y": 40.092805752936044, "z": 202.95895964487252, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.3706868162215615, "steering_wheel_angle": -0.043, "front_wheel_angle": -0.0019758552115223572, "heading_rate": -0.00530239959674421, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061253.4644747}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.87, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.043, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061253.4644747}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061253.5646408, "x": -88.23556436895211, "y": 40.092805752936044, "z": 202.95895964487252, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.340958816221562, "steering_wheel_angle": -0.043, "front_wheel_angle": -0.0019758552115223572, "heading_rate": -0.005178908485320763, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061253.5644717}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.71, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.043, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061253.5644717}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061253.6645596, "x": -88.23556436895211, "y": 40.092805752936044, "z": 202.95895964487252, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.295533816221561, "steering_wheel_angle": -0.043, "front_wheel_angle": -0.0019758552115223572, "heading_rate": -0.004985953623721629, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061253.664467}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.043, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061253.664467}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061253.7647016, "x": -88.23556436895211, "y": 40.092805752936044, "z": 202.95895964487252, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.267117816221561, "steering_wheel_angle": -0.043, "front_wheel_angle": -0.0019758552115223572, "heading_rate": -0.004862462512298183, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061253.7645416}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.3, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.043, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061253.7645416}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061253.864641, "x": -88.2356039118293, "y": 40.09280184610366, "z": 202.98602664140424, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.237486816221562, "steering_wheel_angle": -0.043, "front_wheel_angle": -0.0019758552115223572, "heading_rate": -0.004731253206410772, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061253.8645058}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 6.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.043, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061253.8645058}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061253.9646606, "x": -88.2356039118293, "y": 40.09280184610366, "z": 202.98602664140424, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1966388162215615, "steering_wheel_angle": -0.042, "front_wheel_angle": -0.0019298797685140421, "heading_rate": -0.004440236698611837, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061253.964474}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.89, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.042, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061253.964474}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061254.0647273, "x": -88.2356039118293, "y": 40.09280184610366, "z": 202.98602664140424, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.155313816221561, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.004150484286679967, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061254.0644963}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.64, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061254.0644963}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061254.1645858, "x": -88.2356039118293, "y": 40.09280184610366, "z": 202.98602664140424, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.1026788162215615, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.003907636801821033, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061254.1644685}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061254.1644685}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061254.2645566, "x": -88.2356039118293, "y": 40.09280184610366, "z": 202.98602664140424, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.077942816221562, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.003789892566737914, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061254.2644668}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 5.15, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061254.2644668}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061254.364564, "x": -88.23563770849249, "y": 40.09279843517322, "z": 202.978974177528, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.053718816221561, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.0036721483316547944, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061254.3644698}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.82, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061254.3644698}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061254.4645774, "x": -88.23563770849249, "y": 40.09279843517322, "z": 202.978974177528, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -4.005373816221562, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.0034293008467958597, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061254.464486}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.66, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061254.464486}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061254.5646124, "x": -88.23563770849249, "y": 40.09279843517322, "z": 202.978974177528, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9701988162215613, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.0032453254794784854, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061254.5645037}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.41, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061254.5645037}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061254.66459, "x": -88.23563770849249, "y": 40.09279843517322, "z": 202.978974177528, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9483428162215617, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.003127581244395366, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061254.6644704}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 4.25, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061254.6644704}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061254.7647104, "x": -88.23563770849249, "y": 40.09279843517322, "z": 202.978974177528, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.9061668162215617, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.0028920927742291263, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061254.7644727}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.93, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061254.7644727}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061254.8646686, "x": -88.23566415038577, "y": 40.092795714121394, "z": 203.0101759302481, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8611668162215613, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.002627168245292107, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061254.8644767}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061254.8644767}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061254.9645615, "x": -88.23566415038577, "y": 40.092795714121394, "z": 203.0101759302481, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8467428162215613, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.0025388600689797676, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061254.9644673}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.45, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061254.9644673}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061255.0646894, "x": -88.23566415038577, "y": 40.092795714121394, "z": 203.0101759302481, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.8176178162215617, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.0023548847016623933, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061255.0644794}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 3.2, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061255.0644794}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061255.1645582, "x": -88.23566415038577, "y": 40.092795714121394, "z": 203.0101759302481, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7930218162215614, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.0021929863784231033, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061255.164466}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.98, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061255.164466}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061255.2645645, "x": -88.23566415038577, "y": 40.092795714121394, "z": 203.0101759302481, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7715018162215617, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.0020458060845692035, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061255.2644682}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.78, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061255.2644682}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061255.3646314, "x": -88.23568341120838, "y": 40.09279361566096, "z": 203.0509443330458, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7427178162215617, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.0018397536731737444, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061255.3644764}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.5, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061255.3644764}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061255.4645774, "x": -88.23568341120838, "y": 40.09279361566096, "z": 203.0509443330458, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7240788162215614, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.00169993239401254, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061255.4644697}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.31, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061255.4644697}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061255.5645628, "x": -88.23568341120838, "y": 40.09279361566096, "z": 203.0509443330458, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.7015668162215616, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.0015233160413878604, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061255.5644681}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.07, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061255.5644681}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061255.664567, "x": -88.23568341120838, "y": 40.09279361566096, "z": 203.0509443330458, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6845618162215614, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.0013834947622266558, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061255.6644707}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.88, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061255.6644707}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061255.7645638, "x": -88.23568341120838, "y": 40.09279361566096, "z": 203.0509443330458, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6666068162215617, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.0012289554536800613, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061255.7644663}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.67, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061255.7644663}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061255.864557, "x": -88.23569596503832, "y": 40.092792431619834, "z": 203.10762473454398, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6511218162215617, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.0010891341745188567, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061255.864466}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.48, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061255.864466}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061255.964592, "x": -88.23569596503832, "y": 40.092792431619834, "z": 203.10762473454398, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6386418162215617, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.0009713899394357372, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061255.9644978}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.32, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061255.9644978}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061256.0645945, "x": -88.23569596503832, "y": 40.092792431619834, "z": 203.10762473454398, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6252138162215615, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.0008389276749672276, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061256.0644693}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.14, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061256.0644693}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061256.1645887, "x": -88.23569596503832, "y": 40.092792431619834, "z": 203.10762473454398, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.614518816221562, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.0007285424545768028, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061256.1644742}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.99, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061256.1644742}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061256.264619, "x": -88.23569596503832, "y": 40.092792431619834, "z": 203.10762473454398, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.6056138162215614, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.0006328752635717681, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061256.264494}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.86, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061256.264494}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061256.3646123, "x": -88.23570292471537, "y": 40.09279171670449, "z": 203.11512023968763, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5957588162215615, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.0005224900431813435, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061256.3644962}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.71, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061256.3644962}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061256.464699, "x": -88.23570292471537, "y": 40.09279171670449, "z": 203.11512023968763, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5869668162215618, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.0004194638374836138, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061256.46449}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.57, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061256.46449}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061256.5646074, "x": -88.23570292471537, "y": 40.09279171670449, "z": 203.11512023968763, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5803338162215614, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.000338514675863969, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061256.5645044}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.46, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061256.5645044}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061256.6645634, "x": -88.23570292471537, "y": 40.09279171670449, "z": 203.11512023968763, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5733738162215616, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.0002502064995516293, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061256.6644666}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.34, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061256.6644666}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061256.764594, "x": -88.23570292471537, "y": 40.09279171670449, "z": 203.11512023968763, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5677938162215614, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.00017661635262467947, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061256.7644992}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.24, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061256.7644992}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061256.8645835, "x": -88.23570569690898, "y": 40.09279128581824, "z": 203.16032771498092, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.561886816221562, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -9.566719100503472e-05, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061256.8644693}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.13, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061256.8644693}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061256.964625, "x": -88.23570569690898, "y": 40.09279128581824, "z": 203.16032771498092, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5582538162215616, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -4.415408815616987e-05, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061256.9645007}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.06, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061256.9645007}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061257.064616, "x": -88.23570569690898, "y": 40.09279128581824, "z": 203.16032771498092, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.5562218162215617, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -1.4718029385389958e-05, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061257.0645015}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.02, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061257.0645015}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061257.1646385, "x": -88.23570569690898, "y": 40.09279128581824, "z": 203.16032771498092, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061257.1645095}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061257.1645095}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061257.264632, "x": -88.23570569690898, "y": 40.09279128581824, "z": 203.16032771498092, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061257.2645018}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061257.2645018}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061257.3646023, "x": -88.23570632127151, "y": 40.09279127895776, "z": 203.18509798759092, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061257.3644946}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061257.3644946}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061257.464602, "x": -88.23570632127151, "y": 40.09279127895776, "z": 203.18509798759092, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061257.4644935}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061257.4644935}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061257.5646284, "x": -88.23570632127151, "y": 40.09279127895776, "z": 203.18509798759092, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061257.564511}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061257.564511}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061257.6645918, "x": -88.23570632127151, "y": 40.09279127895776, "z": 203.18509798759092, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061257.664469}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061257.664469}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061257.76468, "x": -88.23570632127151, "y": 40.09279127895776, "z": 203.18509798759092, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061257.7645087}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061257.7645087}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061257.864596, "x": -88.23570648373578, "y": 40.09279150391881, "z": 203.17853758950818, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061257.8644695}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061257.8644695}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061257.964608, "x": -88.23570648373578, "y": 40.09279150391881, "z": 203.17853758950818, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061257.9644964}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061257.9644964}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061258.0646718, "x": -88.23570648373578, "y": 40.09279150391881, "z": 203.17853758950818, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061258.064511}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061258.064511}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061258.1645699, "x": -88.23570648373578, "y": 40.09279150391881, "z": 203.17853758950818, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061258.1644652}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061258.1644652}
+{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 2, "t": 1744061258.2645996, "x": -88.23570648373578, "y": 40.09279150391881, "z": 203.17853758950818, "yaw": 2.792526766781833, "pitch": -349065850.39886594, "roll": -349065850.39886594}, "v": 28284271247.461903, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "acceleration": -3.1552178162215614, "steering_wheel_angle": -0.041, "front_wheel_angle": -0.0018839055326036736, "heading_rate": -0.0, "gear": 0, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1744061258.2645006}
+{"vehicle_interface_command": null, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": 0, "accelerator_pedal_position": 0.0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1744061258.2645006}
diff --git a/testing/racing_logs/manual_launch_control/meta.yaml b/testing/racing_logs/manual_launch_control/meta.yaml
new file mode 100644
index 000000000..ff8f42a7c
--- /dev/null
+++ b/testing/racing_logs/manual_launch_control/meta.yaml
@@ -0,0 +1,19 @@
+events:
+- description: Ctrl+C pressed, switching to recovery mode
+ time: 1744061258.339312
+ vehicle_time: 1744061258.2645006
+- description: Mission execution ended
+ time: 1744061258.3477583
+ vehicle_time: 1744061258.2645006
+exit_reason: normal exit
+git_branch: racing
+git_commit_id: 2e36aeb7a55246289008a8f0a7de7f84bdbec5e6
+pipelines:
+- name: drive
+ time: 1744061246.6633348
+ vehicle_time: 1744061246.563198
+- name: recovery
+ time: 1744061258.3413317
+ vehicle_time: 1744061258.2645006
+start_time: 1744061246.5398777
+start_time_human_readable: '2025-04-07 16:27:26'
diff --git a/testing/racing_logs/manual_launch_control/settings.yaml b/testing/racing_logs/manual_launch_control/settings.yaml
new file mode 100644
index 000000000..2c14a1d17
--- /dev/null
+++ b/testing/racing_logs/manual_launch_control/settings.yaml
@@ -0,0 +1,300 @@
+control:
+ longitudinal_control:
+ pid_d: 0.0
+ pid_i: 0.03
+ pid_p: 0.8
+ pure_pursuit:
+ crosstrack_gain: 0.3
+ desired_speed: trajectory
+ launch_control: 0
+ lookahead: 2.0
+ lookahead_scale: 2.0
+ recovery:
+ brake_amount: 0.5
+ brake_speed: 2.0
+model_predictive_controller:
+ dt: 0.1
+ lookahead: 20
+planning:
+ longitudinal_plan:
+ acceleration: 0.5
+ deceleration: 2.0
+ desired_speed: 1.0
+ max_deceleration: 6.0
+ min_deceleration: 0.5
+ mode: real
+ planner: dt
+ yield_deceleration: 0.5
+ yielder: expert
+run:
+ 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:
+ - all
+ 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: Gather data from the GEM vehicle as the operator is driving it manually
+ drive:
+ perception:
+ perception_normalization: StandardPerceptionNormalizer
+ state_estimation: GNSSStateEstimator
+ planning:
+ motion_planning: RouteToTrajectoryPlanner
+ route_planning:
+ args:
+ - GEMstack/knowledge/routes/xyhead_highbay_backlot_p.csv
+ type: StaticRoutePlanner
+ log:
+ components:
+ - state_estimation
+ ros_topics: []
+ vehicle_interface: true
+ mission_execution: StandardExecutor
+ mode: hardware
+ name: launch/gather_data.yaml
+ recovery:
+ planning:
+ trajectory_tracking: recovery.StopTrajectoryTracker
+ replay:
+ components: []
+ log: null
+ ros_topics: []
+ require_engaged: false
+ variants:
+ log_ros:
+ run:
+ 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
+ vehicle_interface: gem_hardware.GEMHardwareInterface
+simulator:
+ dt: 0.01
+ gnss_emulator:
+ dt: 0.05
+ real_time_multiplier: 1.0
+vehicle:
+ calibration:
+ calibration_date: '2025-02-25'
+ front_camera:
+ center_position:
+ - 1.75864913
+ - 0.01238124
+ - 1.54408419
+ reference: rear_axle_center
+ rotation:
+ - - 0.00349517
+ - -0.03239524
+ - 0.99946903
+ - - -0.99996547
+ - 0.00742285
+ - 0.0037375
+ - - -0.00753999
+ - -0.99944757
+ - -0.03236817
+ gnss_location:
+ - 1.1
+ - 0
+ - 1.62
+ gnss_yaw: 0.0
+ rear_axle_height: 0.2794
+ reference: rear_axle_center
+ top_lidar:
+ position:
+ - 1.1
+ - 0.03773044170906172
+ - 1.9525244316515322
+ reference: rear_axle_center
+ rotation:
+ - - 0.99941328
+ - 0.02547416
+ - 0.02289458
+ - - -0.02530855
+ - 0.99965159
+ - -0.00749488
+ - - -0.02307753
+ - 0.00691106
+ - 0.99970979
+ control_defaults:
+ accelerator_pedal_speed: 3.0
+ brake_pedal_speed: 3.0
+ steering_wheel_speed: 4.0
+ dynamics:
+ acceleration_deadband: 0.1
+ acceleration_model: hang_v1
+ accelerator_active_range:
+ - 0.2
+ - 1.0
+ aerodynamic_drag_coefficient: 0.01
+ brake_active_range:
+ - 0.5
+ - 1
+ gravity: 9.81
+ internal_dry_deceleration: 0.2
+ internal_viscous_deceleration: 0.05
+ lateral_friction: 1.0
+ longitudinal_friction: 1.0
+ mass: 700.0
+ max_accelerator_acceleration:
+ - 0.0
+ - 5.0
+ max_accelerator_acceleration_reverse: 2.5
+ max_accelerator_power:
+ - 0.0
+ - 5000.0
+ max_accelerator_power_reverse: 5000.0
+ max_brake_deceleration: 8.0
+ pedal_mapping_function: linear
+ velocity_scaling_factor: 0.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/gem/racing2/src/GEMstack/GEMstack/knowledge/vehicle/model/gem_e4.urdf
+ wheel_radius: 0.33
+ wheelbase: 2.56
+ width: 1.7
+ limits:
+ max_acceleration: 3.0
+ max_accelerator_pedal: 1.0
+ max_brake_pedal: 1.0
+ max_deceleration: 5.0
+ max_reverse_speed: 2.5
+ max_speed: 10.0
+ max_steering_rate: 4.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/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_gg_diagram.py b/testing/test_gg_diagram.py
new file mode 100644
index 000000000..160286d3d
--- /dev/null
+++ b/testing/test_gg_diagram.py
@@ -0,0 +1,309 @@
+import numpy as np
+import matplotlib.pyplot as plt
+
+import sys
+import os
+sys.path.append(os.getcwd())
+
+import json
+import matplotlib.pyplot as plt
+import numpy as np
+# from GEMstack.mathutils.transforms import lat_lon_to_xy
+
+from pyproj import Proj, Transformer
+from scipy.spatial import ConvexHull
+
+def latlon_to_xy(latitudes, longitudes, origin_lat, origin_lon):
+ """
+ Converts lat/lon to local X/Y coordinates in meters using a local ENU projection.
+
+ latitudes, longitudes: arrays of GPS coordinates
+ origin_lat, origin_lon: reference point (usually the first point)
+
+ Returns: xs, ys (in meters, relative to origin)
+ """
+ # WGS84 to ENU local projection (east-north-up)
+ transformer = Transformer.from_crs(
+ "epsg:4326", # WGS84 lat/lon
+ f"+proj=tmerc +lat_0={origin_lat} +lon_0={origin_lon} +k=1 +x_0=0 +y_0=0 +ellps=WGS84",
+ always_xy=True
+ )
+
+ xs, ys = transformer.transform(longitudes, latitudes)
+ return xs, ys
+
+
+def parse_behavior_log(filename):
+ """
+ Parses the behavior log file and extracts the following data:
+ - vehicle time
+ - vehicle acceleration
+ - vehicle heading rate
+ - speed
+ """
+ times = []
+ accelerations = []
+ heading_rates = []
+ speeds = []
+ xs = []
+ ys = []
+ ref_lat = 0.0
+ ref_long = 0.0
+
+ with open(filename, 'r') as f:
+ for idx, line in enumerate(f):
+ try:
+ entry = json.loads(line)
+ except json.JSONDecodeError:
+ print(f"Skipping invalid JSON line: {line.strip()}")
+ continue
+ # Process vehicle state data
+ if "vehicle" in entry:
+ t = entry.get("time")
+ vehicle_data = entry["vehicle"].get("data", {})
+ acceleration = vehicle_data.get("acceleration")
+ heading_rate = vehicle_data.get("heading_rate")
+ speed = vehicle_data.get("v")
+ # print(speed)
+ # pose_data = vehicle_data["pose"].get("pose")
+ frame = vehicle_data["pose"].get("frame")
+ x = vehicle_data["pose"].get("x")
+ y = vehicle_data["pose"].get("y")
+ if idx == 0:
+ ref_lat = y
+ ref_long = x
+ x, y = latlon_to_xy(y,x,ref_lat,ref_long)
+ # Only add if all fields are available
+ if None not in (t, acceleration, heading_rate, speed) and frame != 3:
+ times.append(t)
+ accelerations.append(acceleration)
+ heading_rates.append(heading_rate)
+ speeds.append(speed)
+
+ xs.append(x)
+
+ ys.append(y)
+ # print(len(speeds))
+ # print(len(times))
+ return np.array(times), np.array(xs), np.array(ys), np.array(speeds), np.array(accelerations), np.array(heading_rates)
+
+def parse_tracker_csv(filename):
+ """
+ Parses the pure pursuit tracker log file and extracts the following data:
+ - vehicle time (from column index 19)
+ - X position actual (from column index 2)
+ - Y position actual (from column index 5)
+ - X position desired (from column index 11)
+ - Y position desired (from column index 14)
+ """
+
+ data = np.genfromtxt(filename, delimiter=',', skip_header=1)
+ vehicle_time = data[:, 19]
+ cte = data[:, 20]
+ x_actual, y_actual = data[:, 2], data[:, 5]
+ # x_desired, y_desired = data[:, 11], data[:, 14] ### PP
+ x_desired, y_desired = data[:, 8], data[:, 11] #Stanley
+ speed_actual = data[:, -1]
+ des_speed = data[:, -13]
+ return vehicle_time, cte, x_actual, y_actual, x_desired, y_desired, speed_actual, des_speed
+
+def compute_derivative(times, values):
+ """
+ Computes the derivative of array with respect to time.
+ Returns the time array and derivative values.
+ """
+ dt = np.diff(times)
+ dv = np.diff(values)
+ derivative = dv / dt
+ return times[1:], derivative
+
+def moving_average(data, window_size=5):
+ """
+ Simple moving average smoother for 1D array.
+ Pads edges by repeating border values.
+ """
+ pad = window_size // 2
+ padded = np.pad(data, (pad, pad), mode='edge')
+ smoothed = np.convolve(padded, np.ones(window_size) / window_size, mode='valid')
+ return smoothed
+
+def remove_duplicate_positions(times, xs, ys):
+ """
+ Removes consecutive duplicate (x, y) points.
+ Keeps only unique steps in position.
+ """
+ xs = np.array(xs)
+ ys = np.array(ys)
+ times = np.array(times)
+
+ # Compute deltas
+ dx = np.diff(xs)
+ dy = np.diff(ys)
+
+ # Find where movement occurs
+ moved = (dx != 0) | (dy != 0)
+
+ # Always keep the first point
+ keep_idx = np.insert(moved, 0, True)
+
+ return times[keep_idx], xs[keep_idx], ys[keep_idx]
+
+def compute_gs(times, xs, ys, speeds, accelerations, heading_rates):
+ # vxs = np.gradient(xs, times)
+ # vys = np.gradient(ys, times)
+ times = times - times[0]
+ dx = np.diff(xs)
+ dy = np.diff(ys)
+ dt = np.diff(times)
+
+ vxs = dx/dt
+ vys = dy/dt
+ vs = np.sqrt(vxs**2 + vys**2)
+
+ vs = moving_average(vs, window_size=7)
+
+ valid_mask = vs > 1e-6 # small threshold to avoid float noise
+ vs = vs[valid_mask]
+ times = times[:-1]
+ times = times[valid_mask]
+
+ long_accels = np.gradient(vs, times)
+
+ accel_valid_mask = np.abs(long_accels) < 5
+
+ psis = np.arctan2(vys, vxs)
+ psis = psis[valid_mask]
+ psi_mask = psis > 1e-6
+ psis = psis[psi_mask]
+ times = times[psi_mask]
+ vs = vs[psi_mask]
+ long_accels = long_accels[psi_mask]
+
+ yaw_rates = np.gradient(psis, times)
+
+ lat_accels = yaw_rates * vs
+ g = 9.81
+ longitudinal_gs = long_accels / g
+ lateral_gs = lat_accels / g
+
+ print("max long accel: " + str(np.max(long_accels)))
+ print("min long accel: " + str(np.min(long_accels)))
+ print("max lat accel: " + str(np.max(lat_accels)))
+
+
+ return longitudinal_gs, lateral_gs, vs, lat_accels, long_accels, times, valid_mask
+
+def plot_position(axis, x_actual, y_actual, x_desired=None, y_desired=None, safe_thresh=1, unsafe_thresh=2.5):
+ """Plots vehicle actual and desired positions vs. time"""
+ # position_error = np.sqrt((x_desired - x_actual) ** 2 + (y_desired - y_actual) ** 2)
+
+ axis.plot(y_desired, x_desired, linestyle='--', color='blue', label='Desired')
+ axis.plot(y_actual, x_actual, color="black", linewidth=0.8, alpha=0.5, label='Actual')
+
+ axis.set_xlabel("Y Position (m)")
+ axis.set_ylabel("X Position (m)")
+ axis.set_title("GEM Position")
+ axis.legend()
+ axis.grid(True)
+
+def plot_speeds(axis, time, speed_actual, comptued_speed = None):
+ if comptued_speed is not None:
+ axis.plot(time, comptued_speed, label='computed speed')
+ axis.plot(time, speed_actual, linestyle="--")#, label='current speed')
+ axis.set_xlabel("time")
+ axis.set_ylabel("speed m/s")
+ axis.set_title("GEM Speed")
+ # axis.legend()
+ axis.grid(True)
+
+def plot_accelerations(axis, accelerations, time):
+ axis.plot(time, accelerations, linestyle='--')#,label='acceleration')
+ axis.set_xlabel("time")
+ axis.set_ylabel("accel m/s^2")
+ axis.set_title("GEM Accelerations")
+ # axis.legend()
+ axis.grid(True)
+
+def plot_gg_diagram(axis, longitudinal_gs, lateral_gs):
+ """Plots gg diagram"""
+ # Plot G-G diagram
+ axis.scatter(lateral_gs, longitudinal_gs, alpha=0.5, label="Data Points")
+
+ # draw op envelope
+ gy_full = np.concatenate([longitudinal_gs, longitudinal_gs])
+ gx_full = np.concatenate([lateral_gs, -lateral_gs])
+
+ points = np.vstack((gx_full, gy_full)).T
+ hull = ConvexHull(points)
+ for simplex in hull.simplices:
+ axis.plot(points[simplex, 0], points[simplex, 1], 'r-')
+ axis.fill(points[hull.vertices, 0], points[hull.vertices, 1],
+ 'r', alpha=0.1, label='Operating Envelope')
+
+ axis.axhline(0, color='black', linewidth=0.8)
+ axis.axvline(0, color='black', linewidth=0.8)
+ axis.set_xlabel("Lateral Acceleration (g)")
+ axis.set_ylabel("Longitudinal Acceleration (g)")
+ axis.set_title("G-G Diagram and Operating Envelope")
+ axis.legend()
+ axis.grid()
+
+
+
+if __name__=='__main__':
+ if len(sys.argv) != 2:
+ print("Usage: python test_comfort_metrics.py ")
+ sys.exit(1)
+
+ log_dir = sys.argv[1]
+ behavior_file = os.path.join(log_dir, "behavior.json")
+ tracker_file = os.path.join(log_dir, "StanleyTrajectoryTracker_debug.csv")
+ # tracker_file = os.path.join(log_dir, "PurePursuitTrajectoryTracker_debug.csv")
+
+ # if behavior.json doesn't exist, print error and exit
+ if not os.path.exists(behavior_file):
+ print("Error: behavior.json file is missing in log folder.")
+ sys.exit(1)
+
+ # Parse behavior log file and compute metrics
+ times, xs, ys, speeds, accelerations, heading_rates = parse_behavior_log(behavior_file)
+ time_jerk, jerk = compute_derivative(times, accelerations)
+ time_heading_acc, heading_acc = compute_derivative(times, heading_rates)
+
+ times, xs, ys = remove_duplicate_positions(times, xs, ys)
+ longitudinal_gs, lateral_gs, vs, lat_accels, long_accels, times, valid_mask = compute_gs(times, xs, ys, speeds, accelerations, heading_rates)
+
+ vehicle_time, cte, x_actual, y_actual, x_desired, y_desired, speed_actual, des_speed = parse_tracker_csv(tracker_file)
+
+ fig, axs = plt.subplots(2, 2, figsize=(12, 8))
+ plot_gg_diagram(axs[0, 0], longitudinal_gs, lateral_gs)
+ # plot_position(axs[0, 1], xs, ys) #, x_desired, y_desired)
+ plot_position(axs[0, 1], x_actual, y_actual, x_desired, y_desired)
+ # plot_speeds(axs[1, 0], times, vs)
+ plot_speeds(axs[1, 0], vehicle_time, des_speed, speed_actual)
+
+ plot_accelerations(axs[1, 1], long_accels, times)
+ plt.tight_layout()
+ name = "gg_diagram.png"
+ file_path = os.path.join(log_dir, name)
+
+ plt.savefig(file_path, dpi=300, format='png')
+ print(f"Plots saved as {name}")
+
+ plt.show()
+
+ # # Pure pursuit tracker file exists: parse and plot all metrics
+ # if os.path.exists(tracker_file):
+
+ # longitudinal_gs, lateral_gs, calculated_speed, lat_accels, long_accels, times, valid_mask = compute_gs(vehicle_time, x_actual, y_actual, speed_actual)
+ # fig, axs = plt.subplots(2, 2)
+ # plot_gg_diagram(axs[0, 0], longitudinal_gs, lateral_gs)
+ # plot_position(axs[0, 1], x_actual, y_actual, x_desired, y_desired)
+ # plot_speeds(axs[1, 0], speed_actual[valid_mask], calculated_speed, times)
+
+ # plot_accelerations(axs[1, 1], long_accels, times)
+
+ # plt.show()
+ # # Pure pursuit tracker file is missing: plot only behavior.json metrics
+ # else:
+ # print("Tracker file is missing. Skipping cross track error and vehicle position plots.")
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, "steerin